Class GazeboRosForce

Inheritance Relationships

Base Type

  • public gazebo::ModelPlugin

Class Documentation

class GazeboRosForce : public gazebo::ModelPlugin

This plugin collects data from a ROS topic and applies wrench to a link accordingly.

The last received force will be continuously added to the link at every simulation iteration. Send an empty / zero message to stop applying a force.

Example Usage:

<plugin name="gazebo_ros_force" filename="libgazebo_ros_force.so">

  <ros>

    <!-- Add a namespace -->
    <namespace>/test</namespace>

    <!-- Remap the default topic -->
    <remapping>gazebo_ros_force:=force_test</remapping>

  </ros>

  <!-- Name of link within model which will receive the force -->
  <link_name>link</link_name>

  <!-- Frame where the force/torque will be applied (options: world; link)-->
  <force_frame>link</force_frame>

</plugin>

Public Functions

GazeboRosForce()

Constructor.

virtual ~GazeboRosForce()

Destructor.

Protected Functions

void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) override
virtual void OnUpdate()

Optional callback to be called at every simulation iteration.