@@ -262,8 +262,7 @@ controller_interface::return_type JointTrajectoryController::update(
262262 {
263263 RCLCPP_WARN (get_node ()->get_logger (), " Aborted due to command timeout" );
264264
265- traj_msg_external_point_ptr_.reset ();
266- traj_msg_external_point_ptr_.initRT (set_hold_position ());
265+ add_new_trajectory_msg_RT (set_hold_position ());
267266 }
268267
269268 // Check state/goal tolerance
@@ -364,8 +363,7 @@ controller_interface::return_type JointTrajectoryController::update(
364363
365364 RCLCPP_WARN (get_node ()->get_logger (), " Aborted due to state tolerance violation" );
366365
367- traj_msg_external_point_ptr_.reset ();
368- traj_msg_external_point_ptr_.initRT (set_hold_position ());
366+ add_new_trajectory_msg_RT (set_hold_position ());
369367 }
370368 // check goal tolerance
371369 else if (!before_last_point)
@@ -382,8 +380,7 @@ controller_interface::return_type JointTrajectoryController::update(
382380
383381 RCLCPP_INFO (get_node ()->get_logger (), " Goal reached, success!" );
384382
385- traj_msg_external_point_ptr_.reset ();
386- traj_msg_external_point_ptr_.initRT (set_hold_position ());
383+ add_new_trajectory_msg_RT (set_hold_position ());
387384 }
388385 else if (!within_goal_time)
389386 {
@@ -399,8 +396,7 @@ controller_interface::return_type JointTrajectoryController::update(
399396 get_node ()->get_logger (), " Aborted due goal_time_tolerance exceeding by %f seconds" ,
400397 time_difference);
401398
402- traj_msg_external_point_ptr_.reset ();
403- traj_msg_external_point_ptr_.initRT (set_hold_position ());
399+ add_new_trajectory_msg_RT (set_hold_position ());
404400 }
405401 }
406402 }
@@ -409,16 +405,14 @@ controller_interface::return_type JointTrajectoryController::update(
409405 // we need to ensure that there is no pending goal -> we get a race condition otherwise
410406 RCLCPP_ERROR (get_node ()->get_logger (), " Holding position due to state tolerance violation" );
411407
412- traj_msg_external_point_ptr_.reset ();
413- traj_msg_external_point_ptr_.initRT (set_hold_position ());
408+ add_new_trajectory_msg_RT (set_hold_position ());
414409 }
415410 else if (
416411 !before_last_point && !within_goal_time && *(rt_has_pending_goal_.readFromRT ()) == false )
417412 {
418413 RCLCPP_ERROR (get_node ()->get_logger (), " Exceeded goal_time_tolerance: holding position..." );
419414
420- traj_msg_external_point_ptr_.reset ();
421- traj_msg_external_point_ptr_.initRT (set_hold_position ());
415+ add_new_trajectory_msg_RT (set_hold_position ());
422416 }
423417 // else, run another cycle while waiting for outside_goal_tolerance
424418 // to be satisfied (will stay in this state until new message arrives)
@@ -1052,7 +1046,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
10521046 // Should the controller start by holding position at the beginning of active state?
10531047 if (params_.start_with_holding )
10541048 {
1055- add_new_trajectory_msg (set_hold_position ());
1049+ add_new_trajectory_msg_nonRT (set_hold_position ());
10561050 }
10571051 rt_is_holding_.writeFromNonRT (true );
10581052
@@ -1217,7 +1211,7 @@ void JointTrajectoryController::topic_callback(
12171211 // always replace old msg with new one for now
12181212 if (subscriber_is_active_)
12191213 {
1220- add_new_trajectory_msg (msg);
1214+ add_new_trajectory_msg_nonRT (msg);
12211215 rt_is_holding_.writeFromNonRT (false );
12221216 }
12231217};
@@ -1263,7 +1257,7 @@ rclcpp_action::CancelResponse JointTrajectoryController::goal_cancelled_callback
12631257 rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
12641258
12651259 // Enter hold current position mode
1266- add_new_trajectory_msg (set_hold_position ());
1260+ add_new_trajectory_msg_nonRT (set_hold_position ());
12671261 }
12681262 return rclcpp_action::CancelResponse::ACCEPT;
12691263}
@@ -1280,7 +1274,7 @@ void JointTrajectoryController::goal_accepted_callback(
12801274 auto traj_msg =
12811275 std::make_shared<trajectory_msgs::msg::JointTrajectory>(goal_handle->get_goal ()->trajectory );
12821276
1283- add_new_trajectory_msg (traj_msg);
1277+ add_new_trajectory_msg_nonRT (traj_msg);
12841278 rt_is_holding_.writeFromNonRT (false );
12851279 }
12861280
@@ -1552,27 +1546,47 @@ bool JointTrajectoryController::validate_trajectory_msg(
15521546 return true ;
15531547}
15541548
1555- void JointTrajectoryController::add_new_trajectory_msg (
1549+ void JointTrajectoryController::add_new_trajectory_msg_nonRT (
15561550 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg)
15571551{
15581552 traj_msg_external_point_ptr_.writeFromNonRT (traj_msg);
15591553
1560- // compute gains of controller
1554+ // compute control law
15611555 if (traj_contr_)
15621556 {
1557+ // this can take some time; trajectory won't start until control law is computed
15631558 if (traj_contr_->computeControlLawNonRT (traj_msg) == false )
15641559 {
15651560 RCLCPP_ERROR (get_node ()->get_logger (), " Failed to compute gains for trajectory." );
15661561 }
15671562 }
15681563}
15691564
1565+ void JointTrajectoryController::add_new_trajectory_msg_RT (
1566+ const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg)
1567+ {
1568+ // TODO(christophfroehlich): Need a lock-free write here
1569+ // See https://github.com/ros-controls/ros2_controllers/issues/168
1570+ traj_msg_external_point_ptr_.reset ();
1571+ traj_msg_external_point_ptr_.initRT (traj_msg);
1572+
1573+ // compute control law
1574+ if (traj_contr_)
1575+ {
1576+ // this is used for set_hold_position() only -> this should (and must) not take a long time
1577+ if (traj_contr_->computeControlLawRT (traj_msg) == false )
1578+ {
1579+ RCLCPP_ERROR (get_node ()->get_logger (), " Failed to compute gains for trajectory." );
1580+ }
1581+ }
1582+ }
1583+
15701584void JointTrajectoryController::preempt_active_goal ()
15711585{
15721586 const auto active_goal = *rt_active_goal_.readFromNonRT ();
15731587 if (active_goal)
15741588 {
1575- add_new_trajectory_msg (set_hold_position ());
1589+ add_new_trajectory_msg_nonRT (set_hold_position ());
15761590 auto action_res = std::make_shared<FollowJTrajAction::Result>();
15771591 action_res->set__error_code (FollowJTrajAction::Result::INVALID_GOAL);
15781592 action_res->set__error_string (" Current goal cancelled due to new incoming action." );
0 commit comments