32 #ifndef JOINT_STATE_CONTROLLER_JOINT_STATE_CONTROLLER_H 33 #define JOINT_STATE_CONTROLLER_JOINT_STATE_CONTROLLER_H 38 #include <sensor_msgs/JointState.h> 40 #include <boost/shared_ptr.hpp>
ros::Time last_publish_time_
virtual void update(const ros::Time &time, const ros::Duration &)
virtual bool init(hardware_interface::JointStateInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
virtual void starting(const ros::Time &time)
unsigned int num_hw_joints_
Number of joints present in the JointStateInterface, excluding extra joints.
void addExtraJoints(const ros::NodeHandle &nh, sensor_msgs::JointState &msg)
boost::shared_ptr< realtime_tools::RealtimePublisher< sensor_msgs::JointState > > realtime_pub_
std::vector< hardware_interface::JointStateHandle > joint_state_
virtual void stopping(const ros::Time &)
Controller that publishes the state of all joints in a robot.