Skip to content

Commit 100c754

Browse files
authored
[JTC] Fill action error_strings (#887) (#1009)
1 parent b0c1330 commit 100c754

File tree

1 file changed

+10
-6
lines changed

1 file changed

+10
-6
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 10 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -346,6 +346,7 @@ controller_interface::return_type JointTrajectoryController::update(
346346
{
347347
auto result = std::make_shared<FollowJTrajAction::Result>();
348348
result->set__error_code(FollowJTrajAction::Result::PATH_TOLERANCE_VIOLATED);
349+
result->set__error_string("Aborted due to path tolerance violation");
349350
active_goal->setAborted(result);
350351
// TODO(matthew-reynolds): Need a lock-free write here
351352
// See https://github.com/ros-controls/ros2_controllers/issues/168
@@ -362,9 +363,10 @@ controller_interface::return_type JointTrajectoryController::update(
362363
{
363364
if (!outside_goal_tolerance)
364365
{
365-
auto res = std::make_shared<FollowJTrajAction::Result>();
366-
res->set__error_code(FollowJTrajAction::Result::SUCCESSFUL);
367-
active_goal->setSucceeded(res);
366+
auto result = std::make_shared<FollowJTrajAction::Result>();
367+
result->set__error_code(FollowJTrajAction::Result::SUCCESSFUL);
368+
result->set__error_string("Goal successfully reached!");
369+
active_goal->setSucceeded(result);
368370
// TODO(matthew-reynolds): Need a lock-free write here
369371
// See https://github.com/ros-controls/ros2_controllers/issues/168
370372
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
@@ -377,17 +379,19 @@ controller_interface::return_type JointTrajectoryController::update(
377379
}
378380
else if (!within_goal_time)
379381
{
382+
const std::string error_string = "Aborted due to goal_time_tolerance exceeding by " +
383+
std::to_string(time_difference) + " seconds";
384+
380385
auto result = std::make_shared<FollowJTrajAction::Result>();
381386
result->set__error_code(FollowJTrajAction::Result::GOAL_TOLERANCE_VIOLATED);
387+
result->set__error_string(error_string);
382388
active_goal->setAborted(result);
383389
// TODO(matthew-reynolds): Need a lock-free write here
384390
// See https://github.com/ros-controls/ros2_controllers/issues/168
385391
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
386392
rt_has_pending_goal_.writeFromNonRT(false);
387393

388-
RCLCPP_WARN(
389-
get_node()->get_logger(), "Aborted due goal_time_tolerance exceeding by %f seconds",
390-
time_difference);
394+
RCLCPP_WARN(get_node()->get_logger(), error_string.c_str());
391395

392396
traj_msg_external_point_ptr_.reset();
393397
traj_msg_external_point_ptr_.initRT(set_hold_position());

0 commit comments

Comments
 (0)