Class GazeboRosFTSensor
Defined in File gazebo_ros_ft_sensor.hpp
Class Documentation
-
class gazebo_plugins::GazeboRosFTSensor : public ModelPlugin
This is a controller that simulates a 6 dof force and torque sensor on link or joint. For joints, the wrench is reported in the joint child link frame and the measure direction is child-to-parent link. (Force and Torque Feed Back Ground Truth) If <body_name> is specified, the plugin acts as sensor on a link, otherwise if <joint_name> is specified, it acts as a sensor on a joint Example Usage:
<plugin name="gazebo_ros_ft_sensor" filename="libgazebo_ros_ft_sensor.so"> <ros> <!-- Add a namespace --> <namespace>/demo</namespace> <!-- Remap the default topic --> <remapping>wrench:=wrench_demo</remapping> </ros> <!-- Link name --> <body_name>link</body_name> <!-- Set frame id of published message. Used only when sensor used on links --> <frame_name>demo_world</frame_name> <!-- Update rate in Hz, defaults to 0.0, which means as fast as possible --> <update_rate>1</update_rate> <!-- Standard deviation of the noise to be added to the reported wrench messages. --> <gaussian_noise>0.01</gaussian_noise> </plugin>
Protected Functions
-
void Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf) override
-
void Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf) override