Go to the documentation of this file.
30 #ifndef JOINT_STATE_PUBLISHER_PLUGIN_HH
31 #define JOINT_STATE_PUBLISHER_PLUGIN_HH
33 #include <boost/bind.hpp>
34 #include <gazebo/gazebo.hh>
35 #include <gazebo/physics/physics.hh>
36 #include <gazebo/common/common.hh>
42 #include <sensor_msgs/JointState.h>
61 void Load ( physics::ModelPtr _parent, sdf::ElementPtr _sdf );
62 void OnUpdate (
const common::UpdateInfo & _info );
90 #endif //JOINT_STATE_PUBLISHER_PLUGIN_HH
std::string robot_namespace_
void OnUpdate(const common::UpdateInfo &_info)
std::vector< std::string > joint_names_
event::ConnectionPtr updateConnection
common::Time last_update_time_
void publishJointStates()
ros::Publisher joint_state_publisher_
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
GazeboRosJointStatePublisher()
~GazeboRosJointStatePublisher()
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
physics::ModelPtr parent_
sensor_msgs::JointState joint_state_
std::vector< physics::JointPtr > joints_
boost::shared_ptr< ros::NodeHandle > rosnode_
gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55