1818#include < functional>
1919#include < memory>
2020
21+ #include < stdexcept>
2122#include < string>
2223#include < vector>
2324
@@ -180,6 +181,7 @@ controller_interface::return_type JointTrajectoryController::update(
180181 if (has_active_trajectory ())
181182 {
182183 bool first_sample = false ;
184+ TrajectoryPointConstIter start_segment_itr, end_segment_itr;
183185 // if sampling the first time, set the point before you sample
184186 if (!traj_external_point_ptr_->is_sampled_already ())
185187 {
@@ -196,11 +198,15 @@ controller_interface::return_type JointTrajectoryController::update(
196198 }
197199 }
198200
199- // find segment for current timestamp
200- TrajectoryPointConstIter start_segment_itr, end_segment_itr;
201- const bool valid_point = traj_external_point_ptr_->sample (
201+ // Sample expected state from the trajectory
202+ traj_external_point_ptr_->sample (
202203 time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
203204
205+ // Sample setpoint for next control cycle
206+ const bool valid_point = traj_external_point_ptr_->sample (
207+ time + update_period_, interpolation_method_, command_next_, start_segment_itr,
208+ end_segment_itr, false );
209+
204210 if (valid_point)
205211 {
206212 const rclcpp::Time traj_start = traj_external_point_ptr_->time_from_start ();
@@ -276,7 +282,7 @@ controller_interface::return_type JointTrajectoryController::update(
276282 // Update PIDs
277283 for (auto i = 0ul ; i < dof_; ++i)
278284 {
279- tmp_command_[i] = (state_desired_ .velocities [i] * ff_velocity_scale_[i]) +
285+ tmp_command_[i] = (command_next_ .velocities [i] * ff_velocity_scale_[i]) +
280286 pids_[i]->computeCommand (
281287 state_error_.positions [i], state_error_.velocities [i],
282288 (uint64_t )period.nanoseconds ());
@@ -286,7 +292,7 @@ controller_interface::return_type JointTrajectoryController::update(
286292 // set values for next hardware write()
287293 if (has_position_command_interface_)
288294 {
289- assign_interface_from_point (joint_command_interface_[0 ], state_desired_ .positions );
295+ assign_interface_from_point (joint_command_interface_[0 ], command_next_ .positions );
290296 }
291297 if (has_velocity_command_interface_)
292298 {
@@ -296,20 +302,20 @@ controller_interface::return_type JointTrajectoryController::update(
296302 }
297303 else
298304 {
299- assign_interface_from_point (joint_command_interface_[1 ], state_desired_ .velocities );
305+ assign_interface_from_point (joint_command_interface_[1 ], command_next_ .velocities );
300306 }
301307 }
302308 if (has_acceleration_command_interface_)
303309 {
304- assign_interface_from_point (joint_command_interface_[2 ], state_desired_ .accelerations );
310+ assign_interface_from_point (joint_command_interface_[2 ], command_next_ .accelerations );
305311 }
306312 if (has_effort_command_interface_)
307313 {
308314 assign_interface_from_point (joint_command_interface_[3 ], tmp_command_);
309315 }
310316
311317 // store the previous command. Used in open-loop control mode
312- last_commanded_state_ = state_desired_ ;
318+ last_commanded_state_ = command_next_ ;
313319 }
314320
315321 if (active_goal)
@@ -867,6 +873,13 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
867873 std::string (get_node ()->get_name ()) + " /query_state" ,
868874 std::bind (&JointTrajectoryController::query_state_service, this , _1, _2));
869875
876+ if (get_update_rate () == 0 )
877+ {
878+ throw std::runtime_error (" Controller's update rate is set to 0. This should not happen!" );
879+ }
880+ update_period_ =
881+ rclcpp::Duration (0.0 , static_cast <uint32_t >(1.0e9 / static_cast <double >(get_update_rate ())));
882+
870883 return CallbackReturn::SUCCESS;
871884}
872885
0 commit comments