Class GazeboRosJointStatePublisher
Defined in File gazebo_ros_joint_state_publisher.hpp
Class Documentation
-
class gazebo_plugins::GazeboRosJointStatePublisher : public ModelPlugin
Publish the state of joints in simulation to a given ROS topic.
If the joint contains more than one axis, only the state of the first axis is reported.
Example Usage:
<plugin name="gazebo_ros_joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so"> <ros> <!-- Add a namespace --> <namespace>/ny_namespace</namespace> <!-- Remap the default topic --> <remapping>joint_states:=my_joint_states</remapping> </ros> <!-- Update rate in Hertz --> <update_rate>2</update_rate> <!-- Name of joints in the model whose states will be published. --> <joint_name>left_wheel</joint_name> <joint_name>right_wheel</joint_name> <joint_name>elbow</joint_name> <joint_name>shoulder</joint_name> </plugin>