File tree 1 file changed +11
-1
lines changed
joint_trajectory_controller/src
1 file changed +11
-1
lines changed Original file line number Diff line number Diff line change @@ -1032,6 +1032,17 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
1032
1032
controller_interface::CallbackReturn JointTrajectoryController::on_deactivate (
1033
1033
const rclcpp_lifecycle::State &)
1034
1034
{
1035
+ const auto active_goal = *rt_active_goal_.readFromNonRT ();
1036
+ if (active_goal)
1037
+ {
1038
+ rt_has_pending_goal_.writeFromNonRT (false );
1039
+ auto action_res = std::make_shared<FollowJTrajAction::Result>();
1040
+ action_res->set__error_code (FollowJTrajAction::Result::INVALID_GOAL);
1041
+ action_res->set__error_string (" Current goal cancelled during deactivate transition." );
1042
+ active_goal->setCanceled (action_res);
1043
+ rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
1044
+ }
1045
+
1035
1046
for (size_t index = 0 ; index < dof_; ++index )
1036
1047
{
1037
1048
if (has_position_command_interface_)
@@ -1543,7 +1554,6 @@ void JointTrajectoryController::preempt_active_goal()
1543
1554
const auto active_goal = *rt_active_goal_.readFromNonRT ();
1544
1555
if (active_goal)
1545
1556
{
1546
- add_new_trajectory_msg (set_hold_position ());
1547
1557
auto action_res = std::make_shared<FollowJTrajAction::Result>();
1548
1558
action_res->set__error_code (FollowJTrajAction::Result::INVALID_GOAL);
1549
1559
action_res->set__error_string (" Current goal cancelled due to new incoming action." );
You can’t perform that action at this time.
0 commit comments