diff --git a/robot_state_publisher/include/robot_state_publisher/robot_state_publisher.h b/robot_state_publisher/include/robot_state_publisher/robot_state_publisher.h index 402aa92..67c68be 100644 --- a/robot_state_publisher/include/robot_state_publisher/robot_state_publisher.h +++ b/robot_state_publisher/include/robot_state_publisher/robot_state_publisher.h @@ -40,7 +40,7 @@ #include #include #include -#include +#include #include "robot_state_publisher/treefksolverposfull_recursive.hpp" namespace robot_state_publisher{ @@ -68,8 +68,8 @@ private: KDL::Tree tree_; boost::scoped_ptr solver_; std::string root_; - std::string tf_prefix_; - tf::tfMessage tf_msg_; + std::vector transforms_; + tf::TransformBroadcaster tf_broadcaster_; class empty_tree_exception: public std::exception{ virtual const char* what() const throw(){ diff --git a/robot_state_publisher/src/robot_state_publisher.cpp b/robot_state_publisher/src/robot_state_publisher.cpp index 175c029..221fe2e 100644 --- a/robot_state_publisher/src/robot_state_publisher.cpp +++ b/robot_state_publisher/src/robot_state_publisher.cpp @@ -49,12 +49,6 @@ namespace robot_state_publisher{ RobotStatePublisher::RobotStatePublisher(const Tree& tree) :tree_(tree) { - // get tf prefix - NodeHandle n_local("~"); - std::string searched_param; - n_local.searchParam("tf_prefix", searched_param); - n_local.param(searched_param, tf_prefix_, std::string()); - // build tree solver solver_.reset(new TreeFkSolverPosFull_recursive(tree_)); @@ -78,21 +72,19 @@ bool RobotStatePublisher::publishTransforms(const map& joint_pos ROS_ERROR("Could not compute link poses. The tree or the state is invalid."); return false; } - tf_msg_.transforms.resize(link_poses.size()); + transforms_.resize(link_poses.size()); // send transforms to tf - geometry_msgs::TransformStamped trans; tf::Transform tf_frame; unsigned int i = 0; for (map::const_iterator f=link_poses.begin(); f!=link_poses.end(); f++){ - tf::TransformKDLToTF(f->second, tf_frame); - trans.header.stamp = time; - trans.header.frame_id = tf::resolve(tf_prefix_, root_); - trans.child_frame_id = tf::resolve(tf_prefix_, f->first); - tf::transformTFToMsg(tf_frame, trans.transform); - tf_msg_.transforms[i++] = trans; + tf::TransformKDLToTF(f->second, transforms_[i]); + transforms_[i].stamp_ = time; + transforms_[i].frame_id_ = root_; + transforms_[i].child_frame_id_ = f->first; + i++; } - tf_publisher_.publish(tf_msg_); + tf_broadcaster_.sendTransform(transforms_); return true; }