From 61fed2b3de344a91c53ae5c195abb016d017ab32 Mon Sep 17 00:00:00 2001 From: snktshrma Date: Sun, 30 Jun 2024 21:44:10 +0530 Subject: [PATCH] Readme: Add guide for using the 3d gimbal - Update QGC settings image. - Match gimbal limits in README with params. - Remove params not modified from defaults Signed-off-by: Rhys Mainwaring --- README.md | 41 ++++++++++++++++++++++++++++++++++ config/gazebo-iris-gimbal.parm | 27 +++++++++++----------- 2 files changed, 55 insertions(+), 13 deletions(-) diff --git a/README.md b/README.md index cedda898..9aaecec9 100644 --- a/README.md +++ b/README.md @@ -232,6 +232,47 @@ Display the streamed video: gst-launch-1.0 -v udpsrc port=5600 caps='application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264' ! rtph264depay ! avdec_h264 ! videoconvert ! autovideosink sync=false ``` +View the streamed camera frames in [QGC](http://qgroundcontrol.com/): + +`Open QGC > Application Settings > Video Settings > Select UDP h.264 Video Stream & use port 5600` + +![qgc_video_settings](https://github.com/user-attachments/assets/61fa4c2a-37e2-47cf-abcf-9f110d9c2015) + + +### 4. Using 3d Gimbal + +The Iris model is equipped with a 3d gimbal and camera that can be controlled directly in MAVProxy using the RC overrides. + +#### Run Gazebo + +```bash +gz sim -v4 -r iris_runway.sdf +``` + +#### Run ArduPilot SITL with a specified parameter file + +```bash +cd ardupilot + +sim_vehicle.py -D -v ArduCopter -f JSON --add-param-file=$HOME/ardupilot_gazebo/config/gazebo-iris-gimbal.parm --console --map +``` + +Control action for gimbal over RC channel: + +| Action | Channel | RC Low | RC High | +| ------------- | ------------- | ------------- | ------------- | +| Roll | RC6 | Roll Left | Roll Right | +| Pitch | RC7 | Pitch Down | Pitch Up | +| Yaw | RC8 | Yaw Left | Yaw Right | + +Example usage: + +`rc 6 1100` - Gimbal rolls left + +`rc 7 1900` - Gimbal pitch upwards + +`rc 8 1500` - Gimbal yaw neutral + ## Models In addition to the Iris and Zephyr models included here, a selection diff --git a/config/gazebo-iris-gimbal.parm b/config/gazebo-iris-gimbal.parm index 3cf5d186..c2d29622 100644 --- a/config/gazebo-iris-gimbal.parm +++ b/config/gazebo-iris-gimbal.parm @@ -14,17 +14,18 @@ RNGFND1_SCALING 10 RNGFND1_PIN 0 RNGFND1_MAX_CM 5000 -# Gimbal on mount 1 has 2 DOF -MNT1_PITCH_MAX 90 -MNT1_PITCH_MIN -90 -MNT1_ROLL_MAX 90 -MNT1_ROLL_MIN -90 -MNT1_TYPE 1 +# 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 -# Gimbal roll and pitch RC -RC9_OPTION 212 -RC10_OPTION 213 - -# Gimbal roll and pitch servos -SERVO5_FUNCTION 8 -SERVO6_FUNCTION 7 +# Gimbal servo out +SERVO9_FUNCTION 8 # Mount1Roll +SERVO10_FUNCTION 7 # Mount1Pitch +SERVO11_FUNCTION 6 # Mount1Yaw