From 4b496476d3c5cf49a1518e48d349877224dc090b Mon Sep 17 00:00:00 2001 From: wim Date: Mon, 29 Mar 2010 22:38:04 +0000 Subject: [PATCH] change printf to ros_debug, ticket #3932 --- robot_state_publisher/src/treefksolverposfull_recursive.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/robot_state_publisher/src/treefksolverposfull_recursive.cpp b/robot_state_publisher/src/treefksolverposfull_recursive.cpp index bfa7665..7fdf560 100644 --- a/robot_state_publisher/src/treefksolverposfull_recursive.cpp +++ b/robot_state_publisher/src/treefksolverposfull_recursive.cpp @@ -21,6 +21,7 @@ #include "robot_state_publisher/treefksolverposfull_recursive.hpp" +#include #include #include @@ -58,7 +59,7 @@ void TreeFkSolverPosFull_recursive::addFrameToMap(const map& q_i if (this_segment->second.segment.getJoint().getType() != Joint::None){ map::const_iterator jnt_pos = q_in.find(this_segment->second.segment.getJoint().getName()); if (jnt_pos == q_in.end()){ - printf("Warning: TreeFKSolverPosFull Could not find value for joint '%s'. Skipping this tree branch\n", this_segment->first.c_str()); + ROS_DEBUG("Warning: TreeFKSolverPosFull Could not find value for joint '%s'. Skipping this tree branch", this_segment->first.c_str()); return; } jnt_p = jnt_pos->second;