@@ -74,7 +74,7 @@ controller_interface::CallbackReturn ScaledJointTrajectoryController::on_activat
7474}
7575
7676controller_interface::return_type ScaledJointTrajectoryController::update (const rclcpp::Time& time,
77- const rclcpp::Duration& /* period*/ )
77+ const rclcpp::Duration& period)
7878{
7979 if (state_interfaces_.back ().get_name () == scaled_params_.speed_scaling_interface_name ) {
8080 scaling_factor_ = state_interfaces_.back ().get_value ();
@@ -87,189 +87,236 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
8787 return controller_interface::return_type::OK;
8888 }
8989
90- auto resize_joint_trajectory_point = [&](trajectory_msgs::msg::JointTrajectoryPoint& point, size_t size) {
91- point.positions .resize (size);
92- if (has_velocity_state_interface_) {
93- point.velocities .resize (size);
94- }
95- if (has_acceleration_state_interface_) {
96- point.accelerations .resize (size);
97- }
98- };
99- auto compute_error_for_joint = [&](JointTrajectoryPoint& error, int index, const JointTrajectoryPoint& current,
90+ auto compute_error_for_joint = [&](JointTrajectoryPoint& error, size_t index, const JointTrajectoryPoint& current,
10091 const JointTrajectoryPoint& desired) {
10192 // error defined as the difference between current and desired
102- error.positions [index] = angles::shortest_angular_distance (current.positions [index], desired.positions [index]);
103- if (has_velocity_state_interface_ && has_velocity_command_interface_) {
93+ if (normalize_joint_error_[index]) {
94+ // if desired, the shortest_angular_distance is calculated, i.e., the error is
95+ // normalized between -pi<error<pi
96+ error.positions [index] = angles::shortest_angular_distance (current.positions [index], desired.positions [index]);
97+ } else {
98+ error.positions [index] = desired.positions [index] - current.positions [index];
99+ }
100+ if (has_velocity_state_interface_ && (has_velocity_command_interface_ || has_effort_command_interface_)) {
104101 error.velocities [index] = desired.velocities [index] - current.velocities [index];
105102 }
106103 if (has_acceleration_state_interface_ && has_acceleration_command_interface_) {
107104 error.accelerations [index] = desired.accelerations [index] - current.accelerations [index];
108105 }
109106 };
110107
108+ // don't update goal after we sampled the trajectory to avoid any racecondition
109+ const auto active_goal = *rt_active_goal_.readFromRT ();
110+
111111 // Check if a new external message has been received from nonRT threads
112112 auto current_external_msg = traj_external_point_ptr_->get_trajectory_msg ();
113113 auto new_external_msg = traj_msg_external_point_ptr_.readFromRT ();
114- if (current_external_msg != *new_external_msg) {
114+ // Discard, if a goal is pending but still not active (somewhere stuck in goal_handle_timer_)
115+ if (current_external_msg != *new_external_msg && (*(rt_has_pending_goal_.readFromRT ()) && !active_goal) == false ) {
115116 fill_partial_goal (*new_external_msg);
116117 sort_to_local_joint_order (*new_external_msg);
118+ // TODO(denis): Add here integration of position and velocity
117119 traj_external_point_ptr_->update (*new_external_msg);
118120 }
119121
120- JointTrajectoryPoint state_current, state_desired, state_error;
121- const auto joint_num = params_.joints .size ();
122- resize_joint_trajectory_point (state_current, joint_num);
123-
124- // current state update
125- auto assign_point_from_interface = [&, joint_num](std::vector<double >& trajectory_point_interface,
126- const auto & joint_inteface) {
127- for (auto index = 0ul ; index < joint_num; ++index) {
128- trajectory_point_interface[index] = joint_inteface[index].get ().get_value ();
129- }
130- };
131- auto assign_interface_from_point = [&, joint_num](auto & joint_inteface,
132- const std::vector<double >& trajectory_point_interface) {
133- for (auto index = 0ul ; index < joint_num; ++index) {
134- joint_inteface[index].get ().set_value (trajectory_point_interface[index]);
122+ // TODO(anyone): can I here also use const on joint_interface since the reference_wrapper is not
123+ // changed, but its value only?
124+ auto assign_interface_from_point = [&](auto & joint_interface, const std::vector<double >& trajectory_point_interface) {
125+ for (size_t index = 0 ; index < dof_; ++index) {
126+ joint_interface[index].get ().set_value (trajectory_point_interface[index]);
135127 }
136128 };
137129
138- state_current.time_from_start .set__sec (0 );
139-
140- // Assign values from the hardware
141- // Position states always exist
142- assign_point_from_interface (state_current.positions , joint_state_interface_[0 ]);
143- // velocity and acceleration states are optional
144- if (has_velocity_state_interface_) {
145- assign_point_from_interface (state_current.velocities , joint_state_interface_[1 ]);
146- // Acceleration is used only in combination with velocity
147- if (has_acceleration_state_interface_) {
148- assign_point_from_interface (state_current.accelerations , joint_state_interface_[2 ]);
149- } else {
150- // Make empty so the property is ignored during interpolation
151- state_current.accelerations .clear ();
152- }
153- } else {
154- // Make empty so the property is ignored during interpolation
155- state_current.velocities .clear ();
156- state_current.accelerations .clear ();
157- }
130+ // current state update
131+ state_current_.time_from_start .set__sec (0 );
132+ read_state_from_hardware (state_current_);
158133
159134 // currently carrying out a trajectory
160135 if (has_active_trajectory ()) {
161136 // Main Speed scaling difference...
162137 // Adjust time with scaling factor
163138 TimeData time_data;
164139 time_data.time = time;
165- rcl_duration_value_t period = (time_data.time - time_data_.readFromRT ()->time ).nanoseconds ();
166- time_data.period = rclcpp::Duration::from_nanoseconds (scaling_factor_ * period );
140+ rcl_duration_value_t t_period = (time_data.time - time_data_.readFromRT ()->time ).nanoseconds ();
141+ time_data.period = rclcpp::Duration::from_nanoseconds (scaling_factor_ * t_period );
167142 time_data.uptime = time_data_.readFromRT ()->uptime + time_data.period ;
168- rclcpp::Time traj_time = time_data_.readFromRT ()->uptime + rclcpp::Duration::from_nanoseconds (period );
143+ rclcpp::Time traj_time = time_data_.readFromRT ()->uptime + rclcpp::Duration::from_nanoseconds (t_period );
169144 time_data_.writeFromNonRT (time_data);
170145
146+ bool first_sample = false ;
171147 // if sampling the first time, set the point before you sample
172148 if (!traj_external_point_ptr_->is_sampled_already ()) {
173- traj_external_point_ptr_->set_point_before_trajectory_msg (traj_time, state_current);
149+ first_sample = true ;
150+ if (params_.open_loop_control ) {
151+ traj_external_point_ptr_->set_point_before_trajectory_msg (traj_time, last_commanded_state_);
152+ } else {
153+ traj_external_point_ptr_->set_point_before_trajectory_msg (traj_time, state_current_);
154+ }
174155 }
175- resize_joint_trajectory_point (state_error, joint_num);
176156
177157 // find segment for current timestamp
178158 joint_trajectory_controller::TrajectoryPointConstIter start_segment_itr, end_segment_itr;
179- const bool valid_point = traj_external_point_ptr_->sample (
180- traj_time, joint_trajectory_controller::interpolation_methods::InterpolationMethod::VARIABLE_DEGREE_SPLINE,
181- state_desired, start_segment_itr, end_segment_itr);
159+ const bool valid_point = traj_external_point_ptr_->sample (traj_time, interpolation_method_, state_desired_,
160+ start_segment_itr, end_segment_itr);
182161
183162 if (valid_point) {
184- bool abort = false ;
163+ const rclcpp::Time traj_start = traj_external_point_ptr_->time_from_start ();
164+ // this is the time instance
165+ // - started with the first segment: when the first point will be reached (in the future)
166+ // - later: when the point of the current segment was reached
167+ const rclcpp::Time segment_time_from_start = traj_start + start_segment_itr->time_from_start ;
168+ // time_difference is
169+ // - negative until first point is reached
170+ // - counting from zero to time_from_start of next point
171+ double time_difference = time.seconds () - segment_time_from_start.seconds ();
172+ bool tolerance_violated_while_moving = false ;
185173 bool outside_goal_tolerance = false ;
174+ bool within_goal_time = true ;
186175 const bool before_last_point = end_segment_itr != traj_external_point_ptr_->end ();
187176
188- // set values for next hardware write()
189- if (has_position_command_interface_) {
190- assign_interface_from_point (joint_command_interface_[0 ], state_desired.positions );
191- }
192- if (has_velocity_command_interface_) {
193- assign_interface_from_point (joint_command_interface_[1 ], state_desired.velocities );
194- }
195- if (has_acceleration_command_interface_) {
196- assign_interface_from_point (joint_command_interface_[2 ], state_desired.accelerations );
177+ // have we reached the end, are not holding position, and is a timeout configured?
178+ // Check independently of other tolerances
179+ if (!before_last_point && *(rt_is_holding_.readFromRT ()) == false && cmd_timeout_ > 0.0 &&
180+ time_difference > cmd_timeout_) {
181+ RCLCPP_WARN (get_node ()->get_logger (), " Aborted due to command timeout" );
182+
183+ traj_msg_external_point_ptr_.reset ();
184+ traj_msg_external_point_ptr_.initRT (set_hold_position ());
197185 }
198186
199- for ( size_t index = 0 ; index < joint_num; ++index) {
200- // set values for next hardware write()
201- compute_error_for_joint (state_error , index, state_current, state_desired );
187+ // Check state/goal tolerance
188+ for ( size_t index = 0 ; index < dof_; ++index) {
189+ compute_error_for_joint (state_error_ , index, state_current_, state_desired_ );
202190
203- if (before_last_point &&
204- !check_state_tolerance_per_joint (state_error, index, default_tolerances_.state_tolerance [index], true )) {
205- abort = true ;
191+ // Always check the state tolerance on the first sample in case the first sample
192+ // is the last point
193+ if ((before_last_point || first_sample) &&
194+ !check_state_tolerance_per_joint (state_error_, index, default_tolerances_.state_tolerance [index], false ) &&
195+ *(rt_is_holding_.readFromRT ()) == false ) {
196+ tolerance_violated_while_moving = true ;
206197 }
207198 // past the final point, check that we end up inside goal tolerance
208- if (!before_last_point && !check_state_tolerance_per_joint (
209- state_error, index, default_tolerances_.goal_state_tolerance [index], true )) {
199+ if (!before_last_point &&
200+ !check_state_tolerance_per_joint (state_error_, index, default_tolerances_.goal_state_tolerance [index],
201+ false ) &&
202+ *(rt_is_holding_.readFromRT ()) == false ) {
210203 outside_goal_tolerance = true ;
204+
205+ if (default_tolerances_.goal_time_tolerance != 0.0 ) {
206+ if (time_difference > default_tolerances_.goal_time_tolerance ) {
207+ within_goal_time = false ;
208+ }
209+ }
210+ }
211+ }
212+
213+ // set values for next hardware write() if tolerance is met
214+ if (!tolerance_violated_while_moving && within_goal_time) {
215+ if (use_closed_loop_pid_adapter_) {
216+ // Update PIDs
217+ for (auto i = 0ul ; i < dof_; ++i) {
218+ tmp_command_[i] = (state_desired_.velocities [i] * ff_velocity_scale_[i]) +
219+ pids_[i]->computeCommand (state_error_.positions [i], state_error_.velocities [i],
220+ (uint64_t )period.nanoseconds ());
221+ }
222+ }
223+
224+ // set values for next hardware write()
225+ if (has_position_command_interface_) {
226+ assign_interface_from_point (joint_command_interface_[0 ], state_desired_.positions );
211227 }
228+ if (has_velocity_command_interface_) {
229+ if (use_closed_loop_pid_adapter_) {
230+ assign_interface_from_point (joint_command_interface_[1 ], tmp_command_);
231+ } else {
232+ assign_interface_from_point (joint_command_interface_[1 ], state_desired_.velocities );
233+ }
234+ }
235+ if (has_acceleration_command_interface_) {
236+ assign_interface_from_point (joint_command_interface_[2 ], state_desired_.accelerations );
237+ }
238+ if (has_effort_command_interface_) {
239+ assign_interface_from_point (joint_command_interface_[3 ], tmp_command_);
240+ }
241+
242+ // store the previous command. Used in open-loop control mode
243+ last_commanded_state_ = state_desired_;
212244 }
213245
214- const auto active_goal = *rt_active_goal_.readFromRT ();
215246 if (active_goal) {
216247 // send feedback
217248 auto feedback = std::make_shared<FollowJTrajAction::Feedback>();
218249 feedback->header .stamp = time;
219250 feedback->joint_names = params_.joints ;
220251
221- feedback->actual = state_current ;
222- feedback->desired = state_desired ;
223- feedback->error = state_error ;
252+ feedback->actual = state_current_ ;
253+ feedback->desired = state_desired_ ;
254+ feedback->error = state_error_ ;
224255 active_goal->setFeedback (feedback);
225256
226257 // check abort
227- if (abort || outside_goal_tolerance ) {
258+ if (tolerance_violated_while_moving ) {
228259 auto result = std::make_shared<FollowJTrajAction::Result>();
229-
230- if (abort) {
231- RCLCPP_WARN (get_node ()->get_logger (), " Aborted due to state tolerance violation" );
232- result->set__error_code (FollowJTrajAction::Result::PATH_TOLERANCE_VIOLATED);
233- } else if (outside_goal_tolerance) {
234- RCLCPP_WARN (get_node ()->get_logger (), " Aborted due to goal tolerance violation" );
235- result->set__error_code (FollowJTrajAction::Result::GOAL_TOLERANCE_VIOLATED);
236- }
260+ result->set__error_code (FollowJTrajAction::Result::PATH_TOLERANCE_VIOLATED);
237261 active_goal->setAborted (result);
262+ // TODO(matthew-reynolds): Need a lock-free write here
263+ // See https://github.com/ros-controls/ros2_controllers/issues/168
238264 rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
239- }
265+ rt_has_pending_goal_. writeFromNonRT ( false );
240266
241- // check goal tolerance
242- if (!before_last_point) {
267+ RCLCPP_WARN (get_node ()->get_logger (), " Aborted due to state tolerance violation" );
268+
269+ traj_msg_external_point_ptr_.reset ();
270+ traj_msg_external_point_ptr_.initRT (set_hold_position ());
271+ } else if (!before_last_point) { // check goal tolerance
243272 if (!outside_goal_tolerance) {
244273 auto res = std::make_shared<FollowJTrajAction::Result>();
245274 res->set__error_code (FollowJTrajAction::Result::SUCCESSFUL);
246275 active_goal->setSucceeded (res);
276+ // TODO(matthew-reynolds): Need a lock-free write here
277+ // See https://github.com/ros-controls/ros2_controllers/issues/168
247278 rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
279+ rt_has_pending_goal_.writeFromNonRT (false );
248280
249281 RCLCPP_INFO (get_node ()->get_logger (), " Goal reached, success!" );
250- } else if (default_tolerances_.goal_time_tolerance != 0.0 ) {
251- // if we exceed goal_time_toleralance set it to aborted
252- const rclcpp::Time traj_start = traj_external_point_ptr_->get_trajectory_start_time ();
253- const rclcpp::Time traj_end = traj_start + start_segment_itr->time_from_start ;
254-
255- // TODO(anyone): This will break in speed scaling we have to discuss how to handle the goal
256- // time when the robot scales itself down.
257- const double difference = time.seconds () - traj_end.seconds ();
258- if (difference > default_tolerances_.goal_time_tolerance ) {
259- auto result = std::make_shared<FollowJTrajAction::Result>();
260- result->set__error_code (FollowJTrajAction::Result::GOAL_TOLERANCE_VIOLATED);
261- active_goal->setAborted (result);
262- rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
263- RCLCPP_WARN (get_node ()->get_logger (), " Aborted due goal_time_tolerance exceeding by %f seconds" ,
264- difference);
265- }
282+
283+ traj_msg_external_point_ptr_.reset ();
284+ traj_msg_external_point_ptr_.initRT (set_hold_position ());
285+ } else if (!within_goal_time) {
286+ auto result = std::make_shared<FollowJTrajAction::Result>();
287+ result->set__error_code (FollowJTrajAction::Result::GOAL_TOLERANCE_VIOLATED);
288+ active_goal->setAborted (result);
289+ // TODO(matthew-reynolds): Need a lock-free write here
290+ // See https://github.com/ros-controls/ros2_controllers/issues/168
291+ rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
292+ rt_has_pending_goal_.writeFromNonRT (false );
293+
294+ RCLCPP_WARN (get_node ()->get_logger (), " Aborted due goal_time_tolerance exceeding by %f seconds" ,
295+ time_difference);
296+
297+ traj_msg_external_point_ptr_.reset ();
298+ traj_msg_external_point_ptr_.initRT (set_hold_position ());
266299 }
267300 }
301+ } else if (tolerance_violated_while_moving && *(rt_has_pending_goal_.readFromRT ()) == false ) {
302+ // we need to ensure that there is no pending goal -> we get a race condition otherwise
303+ RCLCPP_ERROR (get_node ()->get_logger (), " Holding position due to state tolerance violation" );
304+
305+ traj_msg_external_point_ptr_.reset ();
306+ traj_msg_external_point_ptr_.initRT (set_hold_position ());
307+ } else if (!before_last_point && !within_goal_time && *(rt_has_pending_goal_.readFromRT ()) == false ) {
308+ RCLCPP_ERROR (get_node ()->get_logger (), " Exceeded goal_time_tolerance: holding position..." );
309+
310+ traj_msg_external_point_ptr_.reset ();
311+ traj_msg_external_point_ptr_.initRT (set_hold_position ());
268312 }
313+ // else, run another cycle while waiting for outside_goal_tolerance
314+ // to be satisfied (will stay in this state until new message arrives)
315+ // or outside_goal_tolerance violated within the goal_time_tolerance
269316 }
270317 }
271318
272- publish_state (time, state_desired, state_current, state_error );
319+ publish_state (time, state_desired_, state_current_, state_error_ );
273320 return controller_interface::return_type::OK;
274321}
275322
0 commit comments