diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index d98ca615c3..eea137e426 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -368,7 +368,7 @@ controller_interface::return_type JointTrajectoryController::update( } else if (!within_goal_time) { - std::string error_string = "Aborted due goal_time_tolerance exceeding by " + + const std::string error_string = "Aborted due goal_time_tolerance exceeding by " + std::to_string(time_difference) + " seconds"; auto result = std::make_shared();