@@ -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,20 +87,17 @@ 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- };
9990 auto compute_error_for_joint = [&](JointTrajectoryPoint& error, int 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_) {
@@ -114,103 +111,120 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
114111 if (current_external_msg != *new_external_msg) {
115112 fill_partial_goal (*new_external_msg);
116113 sort_to_local_joint_order (*new_external_msg);
114+ // TODO(denis): Add here integration of position and velocity
117115 traj_external_point_ptr_->update (*new_external_msg);
116+ // set the active trajectory pointer to the new goal
117+ traj_point_active_ptr_ = &traj_external_point_ptr_;
118118 }
119119
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]);
120+ // TODO(anyone): can I here also use const on joint_interface since the reference_wrapper is not
121+ // changed, but its value only?
122+ auto assign_interface_from_point = [&](auto & joint_interface, const std::vector<double >& trajectory_point_interface) {
123+ for (size_t index = 0 ; index < dof_; ++index) {
124+ joint_interface[index].get ().set_value (trajectory_point_interface[index]);
135125 }
136126 };
137127
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- }
128+ // current state update
129+ state_current_.time_from_start .set__sec (0 );
130+ read_state_from_hardware (state_current_);
158131
159132 // currently carrying out a trajectory
160133 if (traj_point_active_ptr_ && (*traj_point_active_ptr_)->has_trajectory_msg ()) {
161134 // Main Speed scaling difference...
162135 // Adjust time with scaling factor
163136 TimeData time_data;
164137 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 );
138+ rcl_duration_value_t t_period = (time_data.time - time_data_.readFromRT ()->time ).nanoseconds ();
139+ time_data.period = rclcpp::Duration::from_nanoseconds (scaling_factor_ * t_period );
167140 time_data.uptime = time_data_.readFromRT ()->uptime + time_data.period ;
168- rclcpp::Time traj_time = time_data_.readFromRT ()->uptime + rclcpp::Duration::from_nanoseconds (period );
141+ rclcpp::Time traj_time = time_data_.readFromRT ()->uptime + rclcpp::Duration::from_nanoseconds (t_period );
169142 time_data_.writeFromNonRT (time_data);
170143
144+ bool first_sample = false ;
171145 // if sampling the first time, set the point before you sample
172146 if (!(*traj_point_active_ptr_)->is_sampled_already ()) {
173- (*traj_point_active_ptr_)->set_point_before_trajectory_msg (traj_time, state_current);
147+ first_sample = true ;
148+ if (params_.open_loop_control ) {
149+ (*traj_point_active_ptr_)->set_point_before_trajectory_msg (traj_time, last_commanded_state_);
150+ } else {
151+ (*traj_point_active_ptr_)->set_point_before_trajectory_msg (traj_time, state_current_);
152+ }
174153 }
175- resize_joint_trajectory_point (state_error, joint_num);
176154
177155 // find segment for current timestamp
178156 joint_trajectory_controller::TrajectoryPointConstIter start_segment_itr, end_segment_itr;
179157 const bool valid_point =
180158 (*traj_point_active_ptr_)
181- ->sample (traj_time,
182- joint_trajectory_controller::interpolation_methods::InterpolationMethod::VARIABLE_DEGREE_SPLINE,
183- state_desired, start_segment_itr, end_segment_itr);
159+ ->sample (traj_time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
184160
185161 if (valid_point) {
186- bool abort = false ;
162+ bool tolerance_violated_while_moving = false ;
187163 bool outside_goal_tolerance = false ;
164+ bool within_goal_time = true ;
165+ double time_difference = 0.0 ;
188166 const bool before_last_point = end_segment_itr != (*traj_point_active_ptr_)->end ();
189167
190- // set values for next hardware write()
191- if (has_position_command_interface_) {
192- assign_interface_from_point (joint_command_interface_[0 ], state_desired.positions );
193- }
194- if (has_velocity_command_interface_) {
195- assign_interface_from_point (joint_command_interface_[1 ], state_desired.velocities );
196- }
197- if (has_acceleration_command_interface_) {
198- assign_interface_from_point (joint_command_interface_[2 ], state_desired.accelerations );
199- }
200-
201- for (size_t index = 0 ; index < joint_num; ++index) {
202- // set values for next hardware write()
203- compute_error_for_joint (state_error, index, state_current, state_desired);
168+ // Check state/goal tolerance
169+ for (size_t index = 0 ; index < dof_; ++index) {
170+ compute_error_for_joint (state_error_, index, state_current_, state_desired_);
204171
205- if (before_last_point &&
206- !check_state_tolerance_per_joint (state_error, index, default_tolerances_.state_tolerance [index], true )) {
207- abort = true ;
172+ // Always check the state tolerance on the first sample in case the first sample
173+ // is the last point
174+ if ((before_last_point || first_sample) &&
175+ !check_state_tolerance_per_joint (state_error_, index, default_tolerances_.state_tolerance [index], false )) {
176+ tolerance_violated_while_moving = true ;
208177 }
209178 // past the final point, check that we end up inside goal tolerance
210179 if (!before_last_point && !check_state_tolerance_per_joint (
211- state_error , index, default_tolerances_.goal_state_tolerance [index], true )) {
180+ state_error_ , index, default_tolerances_.goal_state_tolerance [index], false )) {
212181 outside_goal_tolerance = true ;
182+
183+ if (default_tolerances_.goal_time_tolerance != 0.0 ) {
184+ // if we exceed goal_time_tolerance set it to aborted
185+ const rclcpp::Time traj_start = (*traj_point_active_ptr_)->get_trajectory_start_time ();
186+ const rclcpp::Time traj_end = traj_start + start_segment_itr->time_from_start ;
187+
188+ time_difference = time.seconds () - traj_end.seconds ();
189+
190+ if (time_difference > default_tolerances_.goal_time_tolerance ) {
191+ within_goal_time = false ;
192+ }
193+ }
194+ }
195+ }
196+
197+ // set values for next hardware write() if tolerance is met
198+ if (!tolerance_violated_while_moving && within_goal_time) {
199+ if (use_closed_loop_pid_adapter_) {
200+ // Update PIDs
201+ for (auto i = 0ul ; i < dof_; ++i) {
202+ tmp_command_[i] = (state_desired_.velocities [i] * ff_velocity_scale_[i]) +
203+ pids_[i]->computeCommand (state_error_.positions [i], state_error_.velocities [i],
204+ (uint64_t )period.nanoseconds ());
205+ }
206+ }
207+
208+ // set values for next hardware write()
209+ if (has_position_command_interface_) {
210+ assign_interface_from_point (joint_command_interface_[0 ], state_desired_.positions );
211+ }
212+ if (has_velocity_command_interface_) {
213+ if (use_closed_loop_pid_adapter_) {
214+ assign_interface_from_point (joint_command_interface_[1 ], tmp_command_);
215+ } else {
216+ assign_interface_from_point (joint_command_interface_[1 ], state_desired_.velocities );
217+ }
213218 }
219+ if (has_acceleration_command_interface_) {
220+ assign_interface_from_point (joint_command_interface_[2 ], state_desired_.accelerations );
221+ }
222+ if (has_effort_command_interface_) {
223+ assign_interface_from_point (joint_command_interface_[3 ], tmp_command_);
224+ }
225+
226+ // store the previous command. Used in open-loop control mode
227+ last_commanded_state_ = state_desired_;
214228 }
215229
216230 const auto active_goal = *rt_active_goal_.readFromRT ();
@@ -220,58 +234,60 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
220234 feedback->header .stamp = time;
221235 feedback->joint_names = params_.joints ;
222236
223- feedback->actual = state_current ;
224- feedback->desired = state_desired ;
225- feedback->error = state_error ;
237+ feedback->actual = state_current_ ;
238+ feedback->desired = state_desired_ ;
239+ feedback->error = state_error_ ;
226240 active_goal->setFeedback (feedback);
227241
228242 // check abort
229- if (abort || outside_goal_tolerance) {
243+ if (tolerance_violated_while_moving) {
244+ set_hold_position ();
230245 auto result = std::make_shared<FollowJTrajAction::Result>();
231246
232- if (abort) {
233- RCLCPP_WARN (get_node ()->get_logger (), " Aborted due to state tolerance violation" );
234- result->set__error_code (FollowJTrajAction::Result::PATH_TOLERANCE_VIOLATED);
235- } else if (outside_goal_tolerance) {
236- RCLCPP_WARN (get_node ()->get_logger (), " Aborted due to goal tolerance violation" );
237- result->set__error_code (FollowJTrajAction::Result::GOAL_TOLERANCE_VIOLATED);
238- }
247+ RCLCPP_WARN (get_node ()->get_logger (), " Aborted due to state tolerance violation" );
248+ result->set__error_code (FollowJTrajAction::Result::PATH_TOLERANCE_VIOLATED);
239249 active_goal->setAborted (result);
250+ // TODO(matthew-reynolds): Need a lock-free write here
251+ // See https://github.com/ros-controls/ros2_controllers/issues/168
240252 rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
241- }
253+ // remove the active trajectory pointer so that we stop commanding the hardware
254+ traj_point_active_ptr_ = nullptr ;
242255
243- // check goal tolerance
244- if (!before_last_point) {
256+ // check goal tolerance
257+ } else if (!before_last_point) {
245258 if (!outside_goal_tolerance) {
246259 auto res = std::make_shared<FollowJTrajAction::Result>();
247260 res->set__error_code (FollowJTrajAction::Result::SUCCESSFUL);
248261 active_goal->setSucceeded (res);
262+ // TODO(matthew-reynolds): Need a lock-free write here
263+ // See https://github.com/ros-controls/ros2_controllers/issues/168
249264 rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
265+ // remove the active trajectory pointer so that we stop commanding the hardware
266+ traj_point_active_ptr_ = nullptr ;
250267
251268 RCLCPP_INFO (get_node ()->get_logger (), " Goal reached, success!" );
252- } else if (default_tolerances_.goal_time_tolerance != 0.0 ) {
253- // if we exceed goal_time_toleralance set it to aborted
254- const rclcpp::Time traj_start = (*traj_point_active_ptr_)->get_trajectory_start_time ();
255- const rclcpp::Time traj_end = traj_start + start_segment_itr->time_from_start ;
256-
257- // TODO(anyone): This will break in speed scaling we have to discuss how to handle the goal
258- // time when the robot scales itself down.
259- const double difference = time.seconds () - traj_end.seconds ();
260- if (difference > default_tolerances_.goal_time_tolerance ) {
261- auto result = std::make_shared<FollowJTrajAction::Result>();
262- result->set__error_code (FollowJTrajAction::Result::GOAL_TOLERANCE_VIOLATED);
263- active_goal->setAborted (result);
264- rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
265- RCLCPP_WARN (get_node ()->get_logger (), " Aborted due goal_time_tolerance exceeding by %f seconds" ,
266- difference);
267- }
269+ } else if (!within_goal_time) {
270+ set_hold_position ();
271+ auto result = std::make_shared<FollowJTrajAction::Result>();
272+ result->set__error_code (FollowJTrajAction::Result::GOAL_TOLERANCE_VIOLATED);
273+ active_goal->setAborted (result);
274+ // TODO(matthew-reynolds): Need a lock-free write here
275+ // See https://github.com/ros-controls/ros2_controllers/issues/168
276+ rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
277+ RCLCPP_WARN (get_node ()->get_logger (), " Aborted due goal_time_tolerance exceeding by %f seconds" ,
278+ time_difference);
268279 }
280+ // else, run another cycle while waiting for outside_goal_tolerance
281+ // to be satisfied or violated within the goal_time_tolerance
269282 }
283+ } else if (tolerance_violated_while_moving) {
284+ set_hold_position ();
285+ RCLCPP_ERROR (get_node ()->get_logger (), " Holding position due to state tolerance violation" );
270286 }
271287 }
272288 }
273289
274- publish_state (state_desired, state_current, state_error );
290+ publish_state (state_desired_, state_current_, state_error_ );
275291 return controller_interface::return_type::OK;
276292}
277293
0 commit comments