ArduPilot / ardupilot_gazebo

Plugins and models for vehicle simulation in Gazebo Sim with ArduPilot SITL controllers
GNU Lesser General Public License v3.0
82 stars 78 forks source link

Gimbal: enable gimbal in iris model #43

Closed srmainwaring closed 1 year ago

srmainwaring commented 1 year ago

This PR enables a gimbal and camera sensor in the iris_with_gimbal model. The gimbal has 2 DOF and uses the Gazebo JointPositionController rather than a custom plugin.

Closes #37

Details

  1. Update gimbal models

    • Update joint limits.
    • Rename arm_link, arm_joint to roll_link, roll_joint.
    • Remove blank lines.
  2. Update gimbal in iris

    • Add <name> element when including the gimbal to alias the model name to gimbal.
    • Add control channels for roll and tilt.
    • Enable the joint position controllers to actuate the gimbal joints.
  3. Remove deprecated custom plugin for gimbal control.

    • Remove GimbalSmall2dPlugin as it has been superseded by the JointPositionController system.

Upstream dependencies

The custom Gimbal plugin has been removed in favour of using the JointPositionController that ships with Gazebo Garden. There are two pending upstream patches required to support joints in nested models:

Testing

Edit /worlds/iris_runway.sdf: comment out the iris_with_ardupilot model and uncomment the iris_with_gimbal model.

    <include>
      <!-- <uri>model://iris_with_ardupilot</uri> -->
      <uri>model://iris_with_gimbal</uri>
    </include>

Launch Gazebo:

gz sim -v4 -r iris_runway.sdf

The gimbal may be controlled directly from the command line if the mount parameter MNT1_TYPE has not been set (when MNT1_TYPE is set the servo outputs will override any direct commands):

# tilt gimbal by 1 radian
gz topic -t "/gimbal/cmd_tilt" -m gz.msgs.Double -p "data: 1"

# roll gimbal by 1 radian
gz topic -t "/gimbal/cmd_roll" -m gz.msgs.Double -p "data: 1"

https://user-images.githubusercontent.com/24916364/210021755-be56c06a-5625-4089-b846-8a4602b8d496.mov

The gimbal may be configured in SITL as a Servo Gimbal. The ArduPilot Gazebo plugin has been configured to use SERVO5 and SERVO6 for control with the elements:

<control channel="4">
  <jointName>gimbal::roll_joint</jointName>
  <multiplier>3.14159265</multiplier>
  <offset>-0.5</offset>
  <servo_min>1100</servo_min>
  <servo_max>1900</servo_max>
  <type>COMMAND</type>
  <cmd_topic>/gimbal/cmd_roll</cmd_topic>
  <p_gain>3</p_gain>
</control>

<control channel="5">
  <jointName>gimbal::tilt_joint</jointName>
  <multiplier>3.14159265</multiplier>
  <offset>-0.5</offset>
  <servo_min>1100</servo_min>
  <servo_max>1900</servo_max>
  <type>COMMAND</type>
  <cmd_topic>/gimbal/cmd_tilt</cmd_topic>
  <p_gain>3</p_gain>
</control>

The joint limits are [-90 deg, 90 deg] for both roll and tilt and the MNT1* parameters should be set accordingly.

A custom parameter file is included that modifies the default gazebo-iris.parm for gimbal control:

sim_vehicle.py -D -v ArduCopter -f JSON --add-param-file=$HOME/ardupilot_gazebo/config/gazebo-iris-gimbal.parm --console --map

The gimbal roll and tilt may be controlled using the RC inputs in MAVProxy:

# roll
STABILIZE> rc 9 1100
STABILIZE> rc 9 1900
STABILIZE> rc 9 1500

# tilt
STABILIZE> rc 10 1100
STABILIZE> rc 10 1900
STABILIZE> rc 10 1500
rmackay9 commented 1 year ago

I'm not qualified to review this but having gimbal support in gazebo certainly seems like a good idea.

srmainwaring commented 1 year ago

Thanks @rmackay9. There are a couple of PR's I've submitted to Gazebo which need to be approved before I can merge this as one of the system plugins I've used has a bug which limits it's application to this case.

kufd commented 3 days ago

@MahmutEsadErman look at https://github.com/ArduPilot/ardupilot_gazebo/pull/104/files For me it works as described in readme update