18 #ifndef JOINT_STATES_PUBLISHER_HPP
19 #define JOINT_STATES_PUBLISHER_HPP
25 #include <geometry_msgs/Transform.h>
26 #include <sensor_msgs/JointState.h>
27 #include <tf2_ros/transform_broadcaster.h>
40 inline std::string
topic()
const
50 virtual void publish(
const sensor_msgs::JointState& js_msg,
51 const std::vector<geometry_msgs::TransformStamped>& tf_transforms );
53 virtual void reset( ros::NodeHandle& nh );
std::string topic_
Definition: joint_state.hpp:63
virtual void reset(ros::NodeHandle &nh)
Definition: joint_state.cpp:45
virtual bool isSubscribed() const
Definition: joint_state.cpp:54
virtual void publish(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
Definition: joint_state.cpp:33
ros::Publisher pub_joint_states_
Definition: joint_state.hpp:61
bool is_initialized_
Definition: joint_state.hpp:65
JointStatePublisher(const std::string &topic="/joint_states")
Definition: joint_state.cpp:28
std::string topic() const
Definition: joint_state.hpp:40
Definition: joint_state.hpp:34
boost::shared_ptr< tf2_ros::TransformBroadcaster > tf_broadcasterPtr_
Definition: joint_state.hpp:58
bool isInitialized() const
Definition: joint_state.hpp:45