Skip to content

Commit 251e61c

Browse files
committed
revert to humble to use method
1 parent 6d276c4 commit 251e61c

1 file changed

Lines changed: 4 additions & 4 deletions

File tree

decomposition/meta_gimbal_controller/src/gimbal_position_controller.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -223,8 +223,8 @@ namespace gimbal_controller
223223
double yaw_pos_err = NaN, pitch_pos_err = NaN;
224224
double yaw_vel_ref = NaN;
225225

226-
// std::optional<double> yaw_enc_pos = state_interfaces_[0].get_optional();
227-
std::optional<double> pitch_enc_pos = state_interfaces_[1].get_optional();
226+
// double yaw_enc_pos = state_interfaces_[0].get_value();
227+
double pitch_enc_pos = state_interfaces_[1].get_value();
228228
// Calculate commands
229229
if (!std::isnan(reference_interfaces_[0]) && !std::isnan(reference_interfaces_[1]) && !std::isnan(yaw_pos_fb) &&
230230
!std::isnan(pitch_pos_fb) && !std::isnan(roll_pos_fb) && !std::isnan(yaw_vel_fb) &&
@@ -250,7 +250,7 @@ namespace gimbal_controller
250250
// dm imu is positive up
251251
pitch_pos_ref = -reference_interfaces_[1];
252252
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);
253+
ret_ |= command_interfaces_[3].set_value(pitch_enc_pos + pitch_pos_err);
254254
}
255255
if (!ret_)
256256
{
@@ -276,7 +276,7 @@ namespace gimbal_controller
276276
state_publisher_->msg_.dof_states[1].feedback = pitch_pos_fb;
277277
state_publisher_->msg_.dof_states[1].error = pitch_pos_err;
278278
state_publisher_->msg_.dof_states[1].time_step = period.seconds();
279-
state_publisher_->msg_.dof_states[1].output = *pitch_enc_pos + pitch_pos_err;
279+
state_publisher_->msg_.dof_states[1].output = pitch_enc_pos + pitch_pos_err;
280280
}
281281

282282
state_publisher_->unlockAndPublish();

0 commit comments

Comments
 (0)