@@ -260,8 +260,7 @@ controller_interface::return_type JointTrajectoryController::update(
260260 {
261261 RCLCPP_WARN (get_node ()->get_logger (), " Aborted due to command timeout" );
262262
263- traj_msg_external_point_ptr_.reset ();
264- traj_msg_external_point_ptr_.initRT (set_hold_position ());
263+ add_new_trajectory_msg_RT (set_hold_position ());
265264 }
266265
267266 // Check state/goal tolerance
@@ -362,8 +361,7 @@ controller_interface::return_type JointTrajectoryController::update(
362361
363362 RCLCPP_WARN (get_node ()->get_logger (), " Aborted due to state tolerance violation" );
364363
365- traj_msg_external_point_ptr_.reset ();
366- traj_msg_external_point_ptr_.initRT (set_hold_position ());
364+ add_new_trajectory_msg_RT (set_hold_position ());
367365 }
368366 // check goal tolerance
369367 else if (!before_last_point)
@@ -380,8 +378,7 @@ controller_interface::return_type JointTrajectoryController::update(
380378
381379 RCLCPP_INFO (get_node ()->get_logger (), " Goal reached, success!" );
382380
383- traj_msg_external_point_ptr_.reset ();
384- traj_msg_external_point_ptr_.initRT (set_hold_position ());
381+ add_new_trajectory_msg_RT (set_hold_position ());
385382 }
386383 else if (!within_goal_time)
387384 {
@@ -397,8 +394,7 @@ controller_interface::return_type JointTrajectoryController::update(
397394 get_node ()->get_logger (), " Aborted due goal_time_tolerance exceeding by %f seconds" ,
398395 time_difference);
399396
400- traj_msg_external_point_ptr_.reset ();
401- traj_msg_external_point_ptr_.initRT (set_hold_position ());
397+ add_new_trajectory_msg_RT (set_hold_position ());
402398 }
403399 }
404400 }
@@ -407,16 +403,14 @@ controller_interface::return_type JointTrajectoryController::update(
407403 // we need to ensure that there is no pending goal -> we get a race condition otherwise
408404 RCLCPP_ERROR (get_node ()->get_logger (), " Holding position due to state tolerance violation" );
409405
410- traj_msg_external_point_ptr_.reset ();
411- traj_msg_external_point_ptr_.initRT (set_hold_position ());
406+ add_new_trajectory_msg_RT (set_hold_position ());
412407 }
413408 else if (
414409 !before_last_point && !within_goal_time && *(rt_has_pending_goal_.readFromRT ()) == false )
415410 {
416411 RCLCPP_ERROR (get_node ()->get_logger (), " Exceeded goal_time_tolerance: holding position..." );
417412
418- traj_msg_external_point_ptr_.reset ();
419- traj_msg_external_point_ptr_.initRT (set_hold_position ());
413+ add_new_trajectory_msg_RT (set_hold_position ());
420414 }
421415 // else, run another cycle while waiting for outside_goal_tolerance
422416 // to be satisfied (will stay in this state until new message arrives)
@@ -1086,7 +1080,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
10861080 // Should the controller start by holding position at the beginning of active state?
10871081 if (params_.start_with_holding )
10881082 {
1089- add_new_trajectory_msg (set_hold_position ());
1083+ add_new_trajectory_msg_nonRT (set_hold_position ());
10901084 }
10911085 rt_is_holding_.writeFromNonRT (true );
10921086
@@ -1229,7 +1223,7 @@ void JointTrajectoryController::topic_callback(
12291223 // always replace old msg with new one for now
12301224 if (subscriber_is_active_)
12311225 {
1232- add_new_trajectory_msg (msg);
1226+ add_new_trajectory_msg_nonRT (msg);
12331227 rt_is_holding_.writeFromNonRT (false );
12341228 }
12351229};
@@ -1275,7 +1269,7 @@ rclcpp_action::CancelResponse JointTrajectoryController::goal_cancelled_callback
12751269 rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
12761270
12771271 // Enter hold current position mode
1278- add_new_trajectory_msg (set_hold_position ());
1272+ add_new_trajectory_msg_nonRT (set_hold_position ());
12791273 }
12801274 return rclcpp_action::CancelResponse::ACCEPT;
12811275}
@@ -1292,7 +1286,7 @@ void JointTrajectoryController::goal_accepted_callback(
12921286 auto traj_msg =
12931287 std::make_shared<trajectory_msgs::msg::JointTrajectory>(goal_handle->get_goal ()->trajectory );
12941288
1295- add_new_trajectory_msg (traj_msg);
1289+ add_new_trajectory_msg_nonRT (traj_msg);
12961290 rt_is_holding_.writeFromNonRT (false );
12971291 }
12981292
@@ -1564,27 +1558,47 @@ bool JointTrajectoryController::validate_trajectory_msg(
15641558 return true ;
15651559}
15661560
1567- void JointTrajectoryController::add_new_trajectory_msg (
1561+ void JointTrajectoryController::add_new_trajectory_msg_nonRT (
15681562 const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg)
15691563{
15701564 traj_msg_external_point_ptr_.writeFromNonRT (traj_msg);
15711565
1572- // compute gains of controller
1566+ // compute control law
15731567 if (traj_contr_)
15741568 {
1569+ // this can take some time; trajectory won't start until control law is computed
15751570 if (traj_contr_->computeControlLawNonRT (traj_msg) == false )
15761571 {
15771572 RCLCPP_ERROR (get_node ()->get_logger (), " Failed to compute gains for trajectory." );
15781573 }
15791574 }
15801575}
15811576
1577+ void JointTrajectoryController::add_new_trajectory_msg_RT (
1578+ const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> & traj_msg)
1579+ {
1580+ // TODO(christophfroehlich): Need a lock-free write here
1581+ // See https://github.com/ros-controls/ros2_controllers/issues/168
1582+ traj_msg_external_point_ptr_.reset ();
1583+ traj_msg_external_point_ptr_.initRT (traj_msg);
1584+
1585+ // compute control law
1586+ if (traj_contr_)
1587+ {
1588+ // this is used for set_hold_position() only -> this should (and must) not take a long time
1589+ if (traj_contr_->computeControlLawRT (traj_msg) == false )
1590+ {
1591+ RCLCPP_ERROR (get_node ()->get_logger (), " Failed to compute gains for trajectory." );
1592+ }
1593+ }
1594+ }
1595+
15821596void JointTrajectoryController::preempt_active_goal ()
15831597{
15841598 const auto active_goal = *rt_active_goal_.readFromNonRT ();
15851599 if (active_goal)
15861600 {
1587- add_new_trajectory_msg (set_hold_position ());
1601+ add_new_trajectory_msg_nonRT (set_hold_position ());
15881602 auto action_res = std::make_shared<FollowJTrajAction::Result>();
15891603 action_res->set__error_code (FollowJTrajAction::Result::INVALID_GOAL);
15901604 action_res->set__error_string (" Current goal cancelled due to new incoming action." );
0 commit comments