@@ -135,7 +135,7 @@ controller_interface::return_type JointTrajectoryController::update(
135135 // update gains of controller
136136 // TODO(christophfroehlich) activate this
137137 // once https://github.com/ros-controls/ros2_controllers/pull/761 is merged
138- // if (use_closed_loop_control_law_ )
138+ // if (traj_contr_ )
139139 // {
140140 // if(traj_contr_->updateGainsRT() == false)
141141 // {
@@ -181,11 +181,11 @@ controller_interface::return_type JointTrajectoryController::update(
181181 auto new_external_msg = traj_msg_external_point_ptr_.readFromRT ();
182182 // Discard,
183183 // if a goal is pending but still not active (somewhere stuck in goal_handle_timer_)
184- // and if use_closed_loop_control_law_ : wait until control law is computed by the traj_contr_
184+ // and if traj_contr_ : wait until control law is computed by the traj_contr_
185185 if (
186186 current_external_msg != *new_external_msg &&
187187 (*(rt_has_pending_goal_.readFromRT ()) && !active_goal) == false &&
188- (use_closed_loop_control_law_ == false || traj_contr_->is_valid ()))
188+ (traj_contr_ == nullptr || traj_contr_->is_ready ()))
189189 {
190190 fill_partial_goal (*new_external_msg);
191191 sort_to_local_joint_order (*new_external_msg);
@@ -224,6 +224,11 @@ controller_interface::return_type JointTrajectoryController::update(
224224 {
225225 traj_external_point_ptr_->set_point_before_trajectory_msg (time, state_current_);
226226 }
227+ if (traj_contr_)
228+ {
229+ // set start time of trajectory to traj_contr_
230+ traj_contr_->start (time, traj_external_point_ptr_->time_from_start ());
231+ }
227232 }
228233
229234 // find segment for current timestamp
@@ -296,7 +301,7 @@ controller_interface::return_type JointTrajectoryController::update(
296301 // set values for next hardware write() if tolerance is met
297302 if (!tolerance_violated_while_moving && within_goal_time)
298303 {
299- if (use_closed_loop_control_law_ )
304+ if (traj_contr_ )
300305 {
301306 traj_contr_->computeCommands (
302307 tmp_command_, state_current_, state_error_, state_desired_, time, period);
@@ -1072,7 +1077,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
10721077 last_commanded_state_ = state;
10731078 }
10741079
1075- if (use_closed_loop_control_law_ )
1080+ if (traj_contr_ )
10761081 {
10771082 traj_contr_->activate ();
10781083 }
@@ -1564,7 +1569,7 @@ void JointTrajectoryController::add_new_trajectory_msg(
15641569 traj_msg_external_point_ptr_.writeFromNonRT (traj_msg);
15651570
15661571 // compute gains of controller
1567- if (use_closed_loop_control_law_ )
1572+ if (traj_contr_ )
15681573 {
15691574 if (traj_contr_->computeControlLawNonRT (traj_msg) == false )
15701575 {
0 commit comments