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 e2c5248..402aa92 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 @@ -64,7 +64,6 @@ public: bool publishTransforms(const std::map& joint_positions, const ros::Time& time); private: - ros::NodeHandle n_; ros::Publisher tf_publisher_; KDL::Tree tree_; boost::scoped_ptr solver_; diff --git a/robot_state_publisher/src/robot_state_publisher.cpp b/robot_state_publisher/src/robot_state_publisher.cpp index d214eaa..798090f 100644 --- a/robot_state_publisher/src/robot_state_publisher.cpp +++ b/robot_state_publisher/src/robot_state_publisher.cpp @@ -50,13 +50,15 @@ RobotStatePublisher::RobotStatePublisher(const Tree& tree) :tree_(tree) { // get tf prefix - n_.param("~tf_prefix", tf_prefix_, string()); + NodeHandle n_local("~"); + n_local.param("tf_prefix", tf_prefix_, string()); // build tree solver solver_.reset(new TreeFkSolverPosFull_recursive(tree_)); // advertise tf message - tf_publisher_ = n_.advertise("/tf", 5); + NodeHandle n; + tf_publisher_ = n.advertise("/tf", 5); tf_msg_.transforms.resize(tree.getNrOfSegments()-1); // get the 'real' root segment of the tree, which is the first child of "root"