ArduPilot / ardupilot_gazebo

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

Iris: update iris_with_gimbal model to 3d gimbal #102

Closed srmainwaring closed 1 month ago

srmainwaring commented 2 months ago

Updates https://github.com/ArduPilot/ardupilot_gazebo/pull/86 which was on a main branch preventing maintainer edits.

Action Channel RC Low RC High Min (deg) Max (deg)
Roll RC6 Roll Left Roll Right -30 +30
Pitch RC7 Pitch Dn Pitch Up -135 +45
Yaw RC8 Yaw Left Yaw Right -160 160

Copter params

# Iris is X frame
FRAME_CLASS      1
FRAME_TYPE       1

# Match servo out for motors
MOT_PWM_MIN      1100
MOT_PWM_MAX      1900

# Gimbal on mount 1 has 3 DOF
MNT1_TYPE        1           # Servo
MNT1_PITCH_MAX   45
MNT1_PITCH_MIN   -135
MNT1_ROLL_MAX    30
MNT1_ROLL_MIN    -30
MNT1_YAW_MAX     160
MNT1_YAW_MIN     -160

# Gimbal RC in
RC6_MAX          1900
RC6_MIN          1100
RC6_OPTION       212         # Mount1 Roll
RC7_MAX          1900
RC7_MIN          1100
RC7_OPTION       213         # Mount1 Pitch
RC8_MAX          1900
RC8_MIN          1100
RC8_OPTION       214         # Mount1 Yaw
RC8_REVERSED     0           # Normal
RC9_MAX          1900
RC9_MIN          1100
RC9_OPTION       0           # Do Nothing

# Gimbal servo out
SERVO9_FUNCTION  8           # Mount1Roll
SERVO10_FUNCTION 7           # Mount1Pitch
SERVO11_FUNCTION 6           # Mount1Yaw

Figure: gimbal tracking ROI located at the home position while Iris circles iris-gimbal-3d-roi

The GstCameraPlugin is also enabled by default. To view the video in QGC edit Application Settings > Video Settings. Select UDP h.264 Video Stream and use the default port 5600.

iris-gimbal-3d-qcg

Testing

Tested on macOS Sonoma 14.5 and Ubuntu 22.04 (VM). Both running ArduPilot master with Gazebo Harmonic.

rmackay9 commented 2 months ago

@srmainwaring,

Thanks so much for this. This is quite important for the high-altitude-non-GPS GSoC project!

rmackay9 commented 2 months ago

Hi @srmainwaring,

What should MNT1_TYPE be set to? I think it will be either 1 (Servo) or 7 (BrushlessPWM?)

srmainwaring commented 2 months ago

What should MNT1_TYPE be set to? I think it will be either 1 (Servo) or 7 (BrushlessPWM?)

Forgot to add that: yes MNT1_TYPE should be 1 for servo. Updated PR notes at top.

rmackay9 commented 1 month ago

Hi @srmainwaring,

Sanket, Tridge and I were playing around with this today and noticed a couple of issues:

  1. the servos seem slightly laggy which causes the gimbal to move when the vehicle moves. In our high altitude project we expect that users will use brushless gimbals that will be very stable so we'd like to get close to perfect stabilization
  2. The gimbal's pitch servo seems to be limited to 90 degrees downwards so when the vehicle pitches backwards the gimbal physically can't point downwards

Anyway, thanks again for this though, it is on the critical path for both the HighAlt project and the Visual follow-me project!

srmainwaring commented 1 month ago
  1. the servos seem slightly laggy which causes the gimbal to move when the vehicle moves

There's a couple of possible causes for the lag which I'll look into. The most likely is the PID gains on the servo joint controllers in the simulation.

  1. The gimbal's pitch servo seems to be limited to 90 degrees downwards so when the vehicle pitches backwards the gimbal physically can't point downwards

I'll adjust the joint limits and update the AP params to match the specs for the SIYI A8

Finally, the iris model could also do with a tune. IIRC from some other analysis the default params for gazebo-iris are quite close to the limit where roll oscillations become noticeable. There could be some cross-coupling with the gimbal movement that is also contributing to stability.

rmackay9 commented 1 month ago

Hi @srmainwaring,

Thanks very much! By the way, in the instructions at the top of the PR (and maybe eventually on the wiki or in the README) we should specify what these MNT1_xxx parameters should be set to:

and I wonder if we also need to set these values? They seem to be ok that the defaults 1100 ~ 1900 but just in case

srmainwaring commented 1 month ago

@rmackay9 and @snktshrma - should be much snappier now. The limits now match the SIYI A8. Main change to joint control is reducing the damping (equivalent to increasing the PID gains and max force exerted). The original physics settings were carried over from the model from Gazebo Classic - and correspond to a very stiff joint, not that appropriate for a small gimbal.

Figure: gimbal tracking ROI located at home position (location of axis), response is faster with new settings. iris-gimbal-3d-qcg-stabilized