From c68db8264922a05ca1ba8052d3968229231dda53 Mon Sep 17 00:00:00 2001 From: snktshrma Date: Sun, 30 Jun 2024 21:44:10 +0530 Subject: [PATCH] Gimbal: Added rc channel control readme --- README.md | 40 ++++++++++++++++++++++++++++++++++ config/gazebo-iris-gimbal.parm | 18 +++++++++------ 2 files changed, 51 insertions(+), 7 deletions(-) diff --git a/README.md b/README.md index cedda898..c35330f3 100644 --- a/README.md +++ b/README.md @@ -232,6 +232,46 @@ 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 settings](https://private-user-images.githubusercontent.com/74557164/344478908-f55242f3-cff8-4f81-befd-da68e4df73c6.png?jwt=eyJhbGciOiJIUzI1NiIsInR5cCI6IkpXVCJ9.eyJpc3MiOiJnaXRodWIuY29tIiwiYXVkIjoicmF3LmdpdGh1YnVzZXJjb250ZW50LmNvbSIsImtleSI6ImtleTUiLCJleHAiOjE3MTk3NjQwODUsIm5iZiI6MTcxOTc2Mzc4NSwicGF0aCI6Ii83NDU1NzE2NC8zNDQ0Nzg5MDgtZjU1MjQyZjMtY2ZmOC00ZjgxLWJlZmQtZGE2OGU0ZGY3M2M2LnBuZz9YLUFtei1BbGdvcml0aG09QVdTNC1ITUFDLVNIQTI1NiZYLUFtei1DcmVkZW50aWFsPUFLSUFWQ09EWUxTQTUzUFFLNFpBJTJGMjAyNDA2MzAlMkZ1cy1lYXN0LTElMkZzMyUyRmF3czRfcmVxdWVzdCZYLUFtei1EYXRlPTIwMjQwNjMwVDE2MDk0NVomWC1BbXotRXhwaXJlcz0zMDAmWC1BbXotU2lnbmF0dXJlPTkxYjlmYTkwODFiZmMyY2NjMjVjMWZhNjk1NDZhYjUzOTM1YWUzNjI3ZDljZTQ3NmYzM2I4M2JmNzg5ZGY5MmMmWC1BbXotU2lnbmVkSGVhZGVycz1ob3N0JmFjdG9yX2lkPTAma2V5X2lkPTAmcmVwb19pZD0wIn0.48sEOYbBONNEA-0qYevB7z_NleKW_zL-hNSefu5UYaQ) + +### 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 1000` - Gimbal rolls left + +`rc 7 2000` - 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..cd7e6ff7 100644 --- a/config/gazebo-iris-gimbal.parm +++ b/config/gazebo-iris-gimbal.parm @@ -14,17 +14,21 @@ RNGFND1_SCALING 10 RNGFND1_PIN 0 RNGFND1_MAX_CM 5000 -# Gimbal on mount 1 has 2 DOF +# Gimbal on mount 1 has 3 DOF MNT1_PITCH_MAX 90 MNT1_PITCH_MIN -90 MNT1_ROLL_MAX 90 MNT1_ROLL_MIN -90 +MNT1_YAW_MAX 90 +MNT1_YAW_MIN -90 MNT1_TYPE 1 -# Gimbal roll and pitch RC -RC9_OPTION 212 -RC10_OPTION 213 +# Gimbal roll, pitch and yaw RC +RC6_OPTION 212 +RC7_OPTION 213 +RC8_OPTION 214 -# Gimbal roll and pitch servos -SERVO5_FUNCTION 8 -SERVO6_FUNCTION 7 +# Gimbal roll, pitch and yaw servos +SERVO9_FUNCTION 8 +SERVO10_FUNCTION 7 +SERVO11_FUNCTION 6