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]: Abort goal on deactivate #1517

Merged
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -1000,7 +1000,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_deactivate(
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);
active_goal->setAborted(action_res);
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
}

Expand Down
111 changes: 111 additions & 0 deletions joint_trajectory_controller/test/test_trajectory_actions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -969,6 +969,117 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_allow_nonzero_velocity_at_tr
EXPECT_TRUE(gh_future.get());
}

TEST_P(TestTrajectoryActionsTestParameterized, deactivate_controller_aborts_action)
{
// deactivate velocity tolerance
std::vector<rclcpp::Parameter> params = {
rclcpp::Parameter("constraints.stopped_velocity_tolerance", 0.0)};
SetUpExecutor(params, false, 1.0, 0.0);

// We use our own hardware thread here, as we want to make sure the controller is deactivated
auto controller_thread = std::thread(
[&]()
{
// controller hardware cycle update loop
auto clock = rclcpp::Clock(RCL_STEADY_TIME);
auto now_time = clock.now();
auto last_time = now_time;
rclcpp::Duration wait = rclcpp::Duration::from_seconds(0.5);
auto end_time = last_time + wait;
while (clock.now() < end_time)
{
now_time = clock.now();
traj_controller_->update(now_time, now_time - last_time);
last_time = now_time;
}
RCLCPP_INFO(node_->get_logger(), "Controller hardware thread finished");
traj_controller_->get_node()->deactivate();
std::this_thread::sleep_for(std::chrono::milliseconds(100));
});

std::shared_future<typename GoalHandle::SharedPtr> gh_future;
// send goal
std::vector<double> point_positions{1.0, 2.0, 3.0};
{
std::vector<JointTrajectoryPoint> points;
JointTrajectoryPoint point;
point.time_from_start = rclcpp::Duration::from_seconds(2.5);
point.positions = point_positions;

points.push_back(point);

gh_future = sendActionGoal(points, 1.0, goal_options_);
}

controller_thread.join();

EXPECT_TRUE(gh_future.get());
EXPECT_EQ(rclcpp_action::ResultCode::ABORTED, common_resultcode_);

auto state = traj_controller_->get_state_reference();

// run an update
updateControllerAsync(rclcpp::Duration::from_seconds(0.01));

// There will be no active trajectory upon deactivation, so we can't use the expectCommandPoint
// method.
if (traj_controller_->use_closed_loop_pid_adapter() == false)
{
if (traj_controller_->has_position_command_interface())
{
EXPECT_NEAR(state.positions.at(0), joint_pos_[0], COMMON_THRESHOLD);
EXPECT_NEAR(state.positions.at(1), joint_pos_[1], COMMON_THRESHOLD);
EXPECT_NEAR(state.positions.at(2), joint_pos_[2], COMMON_THRESHOLD);
}

if (traj_controller_->has_velocity_command_interface())
{
EXPECT_EQ(state.velocities.at(0), joint_vel_[0]);
EXPECT_EQ(state.velocities.at(1), joint_vel_[1]);
EXPECT_EQ(state.velocities.at(2), joint_vel_[2]);
}

if (traj_controller_->has_acceleration_command_interface())
{
EXPECT_EQ(0.0, joint_acc_[0]);
EXPECT_EQ(0.0, joint_acc_[1]);
EXPECT_EQ(0.0, joint_acc_[2]);
}

if (traj_controller_->has_effort_command_interface())
{
EXPECT_EQ(0.0, joint_eff_[0]);
EXPECT_EQ(0.0, joint_eff_[1]);
EXPECT_EQ(0.0, joint_eff_[2]);
}
}
else // traj_controller_->use_closed_loop_pid_adapter() == true
{
// velocity or effort PID?
// --> set kp > 0.0 in test
if (traj_controller_->has_velocity_command_interface())
{
for (size_t i = 0; i < 3; i++)
{
EXPECT_TRUE(is_same_sign_or_zero(
state.positions.at(i) - pos_state_interfaces_[i].get_value(), joint_vel_[i]))
<< "test position point " << state.positions.at(i) << ", position state is "
<< pos_state_interfaces_[i].get_value() << ", velocity command is " << joint_vel_[i];
}
}
if (traj_controller_->has_effort_command_interface())
{
for (size_t i = 0; i < 3; i++)
{
EXPECT_TRUE(is_same_sign_or_zero(
state.positions.at(i) - pos_state_interfaces_[i].get_value(), joint_eff_[i]))
<< "test position point " << state.positions.at(i) << ", position state is "
<< pos_state_interfaces_[i].get_value() << ", effort command is " << joint_eff_[i];
}
}
}
}

// position controllers
INSTANTIATE_TEST_SUITE_P(
PositionTrajectoryControllersActions, TestTrajectoryActionsTestParameterized,
Expand Down
Loading