Skip to content

Commit cb1ddfb

Browse files
authored
[JTC] Cancel goal in on_deactivate (ros-controls#962) (ros-controls#970)
1 parent 1f3ce24 commit cb1ddfb

File tree

1 file changed

+11
-1
lines changed

1 file changed

+11
-1
lines changed

Diff for: joint_trajectory_controller/src/joint_trajectory_controller.cpp

+11-1
Original file line numberDiff line numberDiff line change
@@ -1032,6 +1032,17 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
10321032
controller_interface::CallbackReturn JointTrajectoryController::on_deactivate(
10331033
const rclcpp_lifecycle::State &)
10341034
{
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+
10351046
for (size_t index = 0; index < dof_; ++index)
10361047
{
10371048
if (has_position_command_interface_)
@@ -1543,7 +1554,6 @@ void JointTrajectoryController::preempt_active_goal()
15431554
const auto active_goal = *rt_active_goal_.readFromNonRT();
15441555
if (active_goal)
15451556
{
1546-
add_new_trajectory_msg(set_hold_position());
15471557
auto action_res = std::make_shared<FollowJTrajAction::Result>();
15481558
action_res->set__error_code(FollowJTrajAction::Result::INVALID_GOAL);
15491559
action_res->set__error_string("Current goal cancelled due to new incoming action.");

0 commit comments

Comments
 (0)