In need of the simplest example of a working rover sdf

Having followed the Articulated Robotics tutorials, I have a working rover in Gazebo (Harmonic/Humble) that I can drive around. I’m trying to replace the ros2_control bits with ArduPilotPlugin bits.

I can run the wildthumper example well enough (and drive it around with mavproxy). I can copy those bits into my own workspace and launch them correctly. However, for the life of me I can’t replicate that with my own simple robot definition.

This whole thing is such a convoluted mess of plugins, bridges, and other abstractions, Not to mention everything having to do with Gazebo has been renamed three times…I’ve been through every bit of documentation I can find and despite all that, I still don’t really know how to ask the right questions about why what I have isn’t working.

So, instead, can someone point me to the simplest example of an sdf model (with like two wheels and a base) that mavproxy can then drive around?

Thanks

@bentwookie - the wildthumper example is probably a good place to start, since as far as ArduPilot is concerned it uses two PWM channels - one for throttle right and one for throttle left, as it is a skid steer rover. Those inputs are relayed to three wheel joints on each side.

To set your rover up with ArduPilot you’ll need to do the following:

  1. Add an imu sensor to the the base_link. Copy the following element into the bottom of <link name="base_link"> before the closing tag.
      <sensor name="imu_sensor" type="imu">
        <pose degrees="true">0 0 0 180 0 0</pose>
        <always_on>1</always_on>
        <update_rate>1000.0</update_rate>
      </sensor>

The model will need a joint state publisher:

    <plugin filename="gz-sim-joint-state-publisher-system"
      name="gz::sim::systems::JointStatePublisher">
    </plugin>

and an ArduPilotPlugin (here it is assumed the wheel joints are named left_wheel_joint and right_wheel_joint).

    <plugin name="ArduPilotPlugin" filename="ArduPilotPlugin">
      <!-- Port settings -->
      <fdm_addr>127.0.0.1</fdm_addr>
      <fdm_port_in>9002</fdm_port_in>
      <connectionTimeoutMaxCount>5</connectionTimeoutMaxCount>
      <lock_step>1</lock_step>

      <modelXYZToAirplaneXForwardZDown degrees="true">0 0 0 180 0 0</modelXYZToAirplaneXForwardZDown>
      <gazeboXYZToNED degrees="true">0 0 0 180 0 90</gazeboXYZToNED>

      <!-- Sensors -->
      <imuName>base_link::imu_sensor</imuName>

      <!-- 
          SERVO1_FUNCTION   73 (Throttle Left)
          SERVO1_MAX        2000
          SERVO1_MIN        1000
          SERVO1_REVERSED   0
          SERVO1_TRIM       1500
       -->
      <control channel="0">
        <jointName>left_wheel_joint</jointName>
        <useForce>1</useForce>
        <multiplier>46.3</multiplier>
        <offset>-0.5</offset>
        <servo_min>1000</servo_min>
        <servo_max>2000</servo_max>
        <type>VELOCITY</type>
        <p_gain>0.2</p_gain>
        <i_gain>0.06</i_gain>
        <d_gain>0.0001</d_gain>
        <i_max>1</i_max>
        <i_min>-1</i_min>
        <cmd_max>-1.0</cmd_max>
        <cmd_min>0.0</cmd_min>
      </control>

      <!-- 
          SERVO3_FUNCTION   74 (Throttle Right)
          SERVO3_MAX        2000
          SERVO3_MIN        1000
          SERVO3_REVERSED   0
          SERVO3_TRIM       1500
       -->
      <control channel="2">
        <jointName>right_wheel_joint</jointName>
        <useForce>1</useForce>
        <multiplier>46.3</multiplier>
        <offset>-0.5</offset>
        <servo_min>1000</servo_min>
        <servo_max>2000</servo_max>
        <type>VELOCITY</type>
        <p_gain>0.2</p_gain>
        <i_gain>0.06</i_gain>
        <d_gain>0.0001</d_gain>
        <i_max>1</i_max>
        <i_min>-1</i_min>
        <cmd_max>-1.0</cmd_max>
        <cmd_min>0.0</cmd_min>
      </control>
      <control channel="2">
        <jointName>mid_right_wheel_joint</jointName>
        <useForce>1</useForce>
        <multiplier>46.3</multiplier>
        <offset>-0.5</offset>
        <servo_min>1000</servo_min>
        <servo_max>2000</servo_max>
        <type>VELOCITY</type>
        <p_gain>0.2</p_gain>
        <i_gain>0.06</i_gain>
        <d_gain>0.0001</d_gain>
        <i_max>1</i_max>
        <i_min>-1</i_min>
        <cmd_max>-1.0</cmd_max>
        <cmd_min>0.0</cmd_min>
      </control>
    </plugin>

Finally, the world file will need to set up various system plugins to ensure the sensors are active. I’d recommend using one of the runway.sdf examples and replace the imported model with your one.

The standard skid steer rover parameters should be a good start. The guide for the wildthumper SITL_Models/Gazebo/docs/WildThumper.md at master · ArduPilot/SITL_Models · GitHub suggests a command line for SITL:

sim_vehicle.py -v Rover -f rover-skid --model JSON  --console --map

Thank you for your reply! It got me much closer to success. I’m now able to get a simple sdf moving on the Gazebo side using mavproxy.

I’m not sure what the actual fix was. I moved my imu sensor tags inside the base_link link (they were on an adjacent link before). I also changed my joints from continuous to revolute with astronomical limits.

To keep rviz happy I also had to have

    <plugin name="gz::sim::systems::OdometryPublisher"
      filename="gz-sim-odometry-publisher-system">
      <odom_frame>odom</odom_frame>
      <robot_base_frame>base_link</robot_base_frame>
      <dimensions>3</dimensions>
    </plugin>

What ended up working doesn’t seem all that dissimilar from what wasn’t working before. Clearly something was wrong though.

Thanks again for your help! Glad to have some success after a few frustrating days!

1 Like