20 #ifndef __JOINT_STATE_PUBLISHER_HH__ 21 #define __JOINT_STATE_PUBLISHER_HH__ 26 #include <boost/scoped_ptr.hpp> 27 #include <boost/algorithm/string.hpp> 28 #include <gazebo/gazebo.hh> 29 #include <gazebo/common/Plugin.hh> 30 #include <gazebo/common/Event.hh> 31 #include <gazebo/physics/Model.hh> 32 #include <gazebo/physics/Joint.hh> 33 #include <gazebo/physics/World.hh> 35 #include <sensor_msgs/JointState.h> 46 public:
void Load(gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf);
48 public:
void OnUpdate(
const gazebo::common::UpdateInfo &_info);
54 private: gazebo::physics::WorldPtr
world;
56 private: gazebo::physics::ModelPtr
model;
76 #endif // __JOINT_STATE_PUBLISHER_HH__ std::vector< std::string > movingJoints
void OnUpdate(const gazebo::common::UpdateInfo &_info)
bool IsIgnoredJoint(std::string _jointName)
gazebo::event::ConnectionPtr updateConnection
gazebo::physics::WorldPtr world
gazebo::common::Time lastUpdate
gazebo::physics::ModelPtr model
void PublishJointStates()
ros::Publisher jointStatePub
void Load(gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf)
std::string robotNamespace
boost::shared_ptr< ros::NodeHandle > node