Skip to content

Commit b67da05

Browse files
committed
fix gimbal_position_controller build under humble
1 parent 251e61c commit b67da05

1 file changed

Lines changed: 4 additions & 9 deletions

File tree

decomposition/meta_gimbal_controller/src/gimbal_position_controller.cpp

Lines changed: 4 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -230,17 +230,16 @@ namespace gimbal_controller
230230
!std::isnan(pitch_pos_fb) && !std::isnan(roll_pos_fb) && !std::isnan(yaw_vel_fb) &&
231231
!std::isnan(pitch_vel_fb))
232232
{
233-
bool ret_ = true;
234233
if (params_.yaw_gimbal_joint.enable)
235234
{
236235
// Yaw Position (IMU) to velocity (IMU) PID
237236
yaw_pos_ref = reference_interfaces_[0];
238237
yaw_pos_err = angles::shortest_angular_distance(yaw_pos_fb, yaw_pos_ref);
239238
yaw_vel_ref = yaw_pos2vel_pid_->compute_command(yaw_pos_err, period);
240239

241-
ret_ |= command_interfaces_[0].set_value(0.0);
242-
ret_ |= command_interfaces_[1].set_value(yaw_vel_ref);
243-
ret_ |= command_interfaces_[2].set_value(0.0);
240+
command_interfaces_[0].set_value(0.0);
241+
command_interfaces_[1].set_value(yaw_vel_ref);
242+
command_interfaces_[2].set_value(0.0);
244243
}
245244

246245
if (params_.pitch_gimbal_joint.enable)
@@ -250,11 +249,7 @@ namespace gimbal_controller
250249
// dm imu is positive up
251250
pitch_pos_ref = -reference_interfaces_[1];
252251
pitch_pos_err = angles::shortest_angular_distance(-pitch_pos_fb, pitch_pos_ref);
253-
ret_ |= command_interfaces_[3].set_value(pitch_enc_pos + pitch_pos_err);
254-
}
255-
if (!ret_)
256-
{
257-
RCLCPP_ERROR(get_node()->get_logger(), "Failed to set command interfaces");
252+
command_interfaces_[3].set_value(pitch_enc_pos + pitch_pos_err);
258253
}
259254
}
260255
// Publish state

0 commit comments

Comments
 (0)