Class GazeboRosHarness

Inheritance Relationships

Base Type

  • public gazebo::HarnessPlugin

Class Documentation

class GazeboRosHarness : public gazebo::HarnessPlugin

Harness plugin for gazebo. Used to lower a model in a smooth manner Example Usage:

<plugin name="gazebo_ros_harness" filename="libgazebo_ros_harness.so">

  <ros>
    <!-- Add a namespace -->
    <namespace>demo</namespace>
    <remapping>box/harness/velocity:=velocity_demo</remapping>
    <remapping>box/harness/detach:=detach_demo</remapping>
  </ros>
  <!-- set initial harness velocity -->
  <!--<init_vel>-0.1</init_vel>-->

  <joint name="joint1" type="prismatic">
      <!-- The joint that raises or lowers the harness.
       This must be specified within the body of this plugin. -->
      <pose>0 0 0 0 0 0</pose>
      <parent>world</parent>
      <child>link</child>
      <axis>
        <xyz>0 0 1</xyz>
        <dynamics>
          <damping>10</damping>
        </dynamics>
        <limit>
          <lower>-1.5</lower>
          <upper>1.5</upper>
          <effort>10000</effort>
          <velocity>-1</velocity>
          <stiffness>0</stiffness>
          <dissipation>0</dissipation>
        </limit>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
          <limit>
            <cfm>0.0</cfm>
            <erp>0.0</erp>
          </limit>
        </ode>
      </physics>
    </joint>

    <winch>
      <joint>joint1</joint>
      <!-- PID value for velocity control of the winch. -->
      <pos_pid>
        <p>1000000</p>
        <i>0</i>
        <d>0</d>
        <i_min>0</i_min>
        <i_max>0</i_max>
        <cmd_min>-10000</cmd_min>
        <cmd_max>10000</cmd_max>
      </pos_pid>

      <vel_pid>
        <p>10000</p>
        <i>0</i>
        <d>0</d>
        <i_min>0</i_min>
        <i_max>0</i_max>
        <cmd_min>0</cmd_min>
        <cmd_max>10000</cmd_max>
      </vel_pid>
    </winch>

    <!-- Joint to detach. Once the joint is detached, it cannot be
      reattached. This must be a joint specified within the
      body of this plugin. -->
    <detach>joint1</detach>

</plugin>

Public Functions

GazeboRosHarness()

Constructor.

~GazeboRosHarness()

Destructor.

Protected Functions

void OnDetach(const std_msgs::msg::Empty::ConstSharedPtr msg)

Callback for receiving detach messages.

Parameters:

msg[in] Empty message.

void Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf) override