move away from deprecated functions, and do not use root namespace for subscription
This commit is contained in:
parent
1252dd7566
commit
8fbaa701b0
|
@ -63,7 +63,7 @@ public:
|
|||
private:
|
||||
void callbackJointState(const JointStateConstPtr& state);
|
||||
|
||||
NodeHandle n_;
|
||||
NodeHandle n_, n_tilde_;
|
||||
Rate publish_rate_;
|
||||
robot_state_publisher::RobotStatePublisher state_publisher_;
|
||||
Subscriber joint_state_sub_;
|
||||
|
|
|
@ -1,11 +1,13 @@
|
|||
<package>
|
||||
<description brief="This package allows you to publish the state of a robot to the transform library topic">
|
||||
|
||||
This package allows you to publish the state of a robot to the transform library topic. Once the state
|
||||
gets published, it is available to all components in the system using the transform library.
|
||||
The package takes the joint angles of the robot as input and publishes the 3D poses
|
||||
of the robot links, using a kinematic tree model of the robot. The package can both be used
|
||||
as a library and as a ROS node.
|
||||
This package allows you to publish the state of a robot to the
|
||||
transform library topic. Once the state gets published, it is
|
||||
available to all components in the system using the transform
|
||||
library. The package takes the joint angles of the robot as input
|
||||
and publishes the 3D poses of the robot links, using a kinematic
|
||||
tree model of the robot. The package can both be used as a library
|
||||
and as a ROS node.
|
||||
|
||||
</description>
|
||||
<author>Wim Meeussen meeussen@willowgarage.com </author>
|
||||
|
|
|
@ -46,15 +46,15 @@ using namespace robot_state_publisher;
|
|||
|
||||
|
||||
JointStateListener::JointStateListener(const KDL::Tree& tree)
|
||||
: n_("~"), publish_rate_(0.0), state_publisher_(tree)
|
||||
: n_tilde_("~"), publish_rate_(0.0), state_publisher_(tree)
|
||||
{
|
||||
// set publish frequency
|
||||
double publish_freq;
|
||||
n_.param("publish_frequency", publish_freq, 50.0);
|
||||
n_tilde_.param("publish_frequency", publish_freq, 50.0);
|
||||
publish_rate_ = Rate(publish_freq);
|
||||
|
||||
// subscribe to mechanism state
|
||||
joint_state_sub_ = n_.subscribe("/joint_states", 1, &JointStateListener::callbackJointState, this);;
|
||||
joint_state_sub_ = n_.subscribe("joint_states", 1, &JointStateListener::callbackJointState, this);;
|
||||
};
|
||||
|
||||
|
||||
|
|
|
@ -36,7 +36,7 @@
|
|||
|
||||
#include <kdl/tree.hpp>
|
||||
#include <ros/ros.h>
|
||||
#include <kdl_parser/dom_parser.hpp>
|
||||
#include <kdl_parser/kdl_parser.hpp>
|
||||
#include <urdf/model.h>
|
||||
#include "robot_state_publisher/joint_state_listener.h"
|
||||
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
#include <tf/transform_listener.h>
|
||||
#include <boost/thread/thread.hpp>
|
||||
#include <urdf/model.h>
|
||||
#include <kdl_parser/dom_parser.hpp>
|
||||
#include <kdl_parser/kdl_parser.hpp>
|
||||
#include "robot_state_publisher/joint_state_listener.h"
|
||||
|
||||
|
||||
|
@ -74,7 +74,7 @@ protected:
|
|||
|
||||
// constructs a kdl tree from the robot model
|
||||
Tree tree;
|
||||
if (!kdl_parser::treeFromRobotModel(robot_model, tree))
|
||||
if (!kdl_parser::treeFromUrdfModel(robot_model, tree))
|
||||
ROS_ERROR("Failed to extract kdl tree from robot model");
|
||||
|
||||
publisher = new JointStateListener(tree);
|
||||
|
@ -106,7 +106,7 @@ TEST_F(TestPublisher, test)
|
|||
ASSERT_TRUE(tf.canTransform("l_gripper_palm_link", "fl_caster_r_wheel_link", Time()));
|
||||
ASSERT_FALSE(tf.canTransform("base_link", "wim_link", Time()));
|
||||
|
||||
tf::Stamped<tf::Transform> t;
|
||||
tf::StampedTransform t;
|
||||
tf.lookupTransform("base_link", "r_gripper_palm_link",Time(), t );
|
||||
EXPECT_NEAR(t.getOrigin().x(), 0.769198, EPS);
|
||||
EXPECT_NEAR(t.getOrigin().y(), -0.188800, EPS);
|
||||
|
|
Loading…
Reference in New Issue