From 8630382ffa06271e26924e16c9ecda52f69dbad0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Mon, 15 Jan 2024 07:41:34 +0100 Subject: [PATCH] Apply suggestions from code review Co-authored-by: Bence Magyar Co-authored-by: Sai Kishor Kothakota --- .../src/joint_trajectory_controller.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index b8bc75ae17..b0e93b6ecd 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -294,7 +294,7 @@ controller_interface::return_type JointTrajectoryController::update( { auto result = std::make_shared(); result->set__error_code(FollowJTrajAction::Result::PATH_TOLERANCE_VIOLATED); - result->set__error_string("Aborted due to state tolerance violation"); + result->set__error_string("Aborted due to path tolerance violation"); active_goal->setAborted(result); // TODO(matthew-reynolds): Need a lock-free write here // See https://github.com/ros-controls/ros2_controllers/issues/168 @@ -313,7 +313,7 @@ controller_interface::return_type JointTrajectoryController::update( { auto result = std::make_shared(); result->set__error_code(FollowJTrajAction::Result::SUCCESSFUL); - result->set__error_string("Goal reached, success!"); + result->set__error_string("Goal successfully reached!"); active_goal->setSucceeded(result); // TODO(matthew-reynolds): Need a lock-free write here // See https://github.com/ros-controls/ros2_controllers/issues/168 @@ -327,7 +327,7 @@ controller_interface::return_type JointTrajectoryController::update( } else if (!within_goal_time) { - const std::string error_string = "Aborted due goal_time_tolerance exceeding by " + + const std::string error_string = "Aborted due to goal_time_tolerance exceeding by " + std::to_string(time_difference) + " seconds"; auto result = std::make_shared();