Skip to content

Commit 2e9e320

Browse files
committed
Removed access to deleted PidState fields in pub
This commit removes references to the fields that were deleted from the PidState.msg in the publish function, ensuring consistency between the message definition and its usage.
1 parent 8931acc commit 2e9e320

File tree

1 file changed

+0
-4
lines changed

1 file changed

+0
-4
lines changed

src/pid_ros.cpp

-4
Original file line numberDiff line numberDiff line change
@@ -351,10 +351,6 @@ void PidROS::publish_pid_state(double cmd, double error, rclcpp::Duration dt)
351351
rt_state_pub_->msg_.p_gain = gains.p_gain_;
352352
rt_state_pub_->msg_.i_gain = gains.i_gain_;
353353
rt_state_pub_->msg_.d_gain = gains.d_gain_;
354-
rt_state_pub_->msg_.i_max = gains.i_max_;
355-
rt_state_pub_->msg_.i_min = gains.i_min_;
356-
rt_state_pub_->msg_.u_max = gains.u_max_;
357-
rt_state_pub_->msg_.u_min = gains.u_min_;
358354
rt_state_pub_->msg_.trk_tc = gains.trk_tc_;
359355
rt_state_pub_->msg_.output = cmd;
360356
rt_state_pub_->unlockAndPublish();

0 commit comments

Comments
 (0)