Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[JTC] Cancel active goal in on_deactivate #962

Merged
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
12 changes: 11 additions & 1 deletion joint_trajectory_controller/src/joint_trajectory_controller.cpp
Expand Up @@ -975,6 +975,17 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
controller_interface::CallbackReturn JointTrajectoryController::on_deactivate(
const rclcpp_lifecycle::State &)
{
const auto active_goal = *rt_active_goal_.readFromNonRT();
if (active_goal)
{
rt_has_pending_goal_.writeFromNonRT(false);
auto action_res = std::make_shared<FollowJTrajAction::Result>();
action_res->set__error_code(FollowJTrajAction::Result::INVALID_GOAL);
action_res->set__error_string("Current goal cancelled during deactivate transition.");
active_goal->setCanceled(action_res);
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
}

for (size_t index = 0; index < dof_; ++index)
{
if (has_position_command_interface_)
Expand Down Expand Up @@ -1445,7 +1456,6 @@ void JointTrajectoryController::preempt_active_goal()
const auto active_goal = *rt_active_goal_.readFromNonRT();
if (active_goal)
{
add_new_trajectory_msg(set_hold_position());
auto action_res = std::make_shared<FollowJTrajAction::Result>();
action_res->set__error_code(FollowJTrajAction::Result::INVALID_GOAL);
action_res->set__error_string("Current goal cancelled due to new incoming action.");
Expand Down