From 1b4ef808eed01880228a596d7ceb346a71a119ab Mon Sep 17 00:00:00 2001 From: Thomas Timm Andersen Date: Thu, 10 Sep 2015 14:46:18 +0200 Subject: [PATCH] Fixed calls to ROS_ERROR --- src/ur_ros_wrapper.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/ur_ros_wrapper.cpp b/src/ur_ros_wrapper.cpp index 03d246f..d57d036 100644 --- a/src/ur_ros_wrapper.cpp +++ b/src/ur_ros_wrapper.cpp @@ -137,21 +137,21 @@ private: "Received a goal with incorrect joint names: " + outp_joint_names; as_.setAborted(result_, result_.error_string); - ROS_ERROR(result_.error_string.c_str()); + ROS_ERROR("%s",result_.error_string.c_str()); } if (!has_velocities()) { result_.error_code = result_.INVALID_GOAL; result_.error_string = "Received a goal without velocities"; as_.setAborted(result_, result_.error_string); - ROS_ERROR(result_.error_string.c_str()); + ROS_ERROR("%s",result_.error_string.c_str()); } if (!traj_is_finite()) { result_.error_string = "Received a goal with infinites or NaNs"; result_.error_code = result_.INVALID_GOAL; as_.setAborted(result_, result_.error_string); - ROS_ERROR(result_.error_string.c_str()); + ROS_ERROR("%s",result_.error_string.c_str()); } if (!has_limited_velocities()) { @@ -159,7 +159,7 @@ private: result_.error_string = "Received a goal with velocities that are higher than %f", max_velocity_; as_.setAborted(result_, result_.error_string); - ROS_ERROR(result_.error_string.c_str()); + ROS_ERROR("%s",result_.error_string.c_str()); } reorder_traj_joints(goal_.trajectory);