Skip to content

Commit 67dbf7b

Browse files
[JTC] Fill action error_strings (#887)
1 parent 2705ca8 commit 67dbf7b

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
@@ -294,6 +294,7 @@ controller_interface::return_type JointTrajectoryController::update(
294294
{
295295
auto result = std::make_shared<FollowJTrajAction::Result>();
296296
result->set__error_code(FollowJTrajAction::Result::PATH_TOLERANCE_VIOLATED);
297+
result->set__error_string("Aborted due to path tolerance violation");
297298
active_goal->setAborted(result);
298299
// TODO(matthew-reynolds): Need a lock-free write here
299300
// See https://github.com/ros-controls/ros2_controllers/issues/168
@@ -310,9 +311,10 @@ controller_interface::return_type JointTrajectoryController::update(
310311
{
311312
if (!outside_goal_tolerance)
312313
{
313-
auto res = std::make_shared<FollowJTrajAction::Result>();
314-
res->set__error_code(FollowJTrajAction::Result::SUCCESSFUL);
315-
active_goal->setSucceeded(res);
314+
auto result = std::make_shared<FollowJTrajAction::Result>();
315+
result->set__error_code(FollowJTrajAction::Result::SUCCESSFUL);
316+
result->set__error_string("Goal successfully reached!");
317+
active_goal->setSucceeded(result);
316318
// TODO(matthew-reynolds): Need a lock-free write here
317319
// See https://github.com/ros-controls/ros2_controllers/issues/168
318320
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
@@ -325,17 +327,19 @@ controller_interface::return_type JointTrajectoryController::update(
325327
}
326328
else if (!within_goal_time)
327329
{
330+
const std::string error_string = "Aborted due to goal_time_tolerance exceeding by " +
331+
std::to_string(time_difference) + " seconds";
332+
328333
auto result = std::make_shared<FollowJTrajAction::Result>();
329334
result->set__error_code(FollowJTrajAction::Result::GOAL_TOLERANCE_VIOLATED);
335+
result->set__error_string(error_string);
330336
active_goal->setAborted(result);
331337
// TODO(matthew-reynolds): Need a lock-free write here
332338
// See https://github.com/ros-controls/ros2_controllers/issues/168
333339
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
334340
rt_has_pending_goal_.writeFromNonRT(false);
335341

336-
RCLCPP_WARN(
337-
get_node()->get_logger(), "Aborted due goal_time_tolerance exceeding by %f seconds",
338-
time_difference);
342+
RCLCPP_WARN(get_node()->get_logger(), error_string.c_str());
339343

340344
traj_msg_external_point_ptr_.reset();
341345
traj_msg_external_point_ptr_.initRT(set_hold_position());

0 commit comments

Comments
 (0)