Skip to content

Commit c68db82

Browse files
committed
Gimbal: Added rc channel control readme
1 parent d5cfe36 commit c68db82

File tree

2 files changed

+51
-7
lines changed

2 files changed

+51
-7
lines changed

Diff for: README.md

+40
Original file line numberDiff line numberDiff line change
@@ -232,6 +232,46 @@ Display the streamed video:
232232
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
233233
```
234234

235+
View the streamed camera frames in [QGC](http://qgroundcontrol.com/):
236+
237+
`Open QGC > Application Settings > Video Settings > Select UDP h.264 Video Stream & use port 5600`
238+
239+
![QGC settings](https://private-user-images.githubusercontent.com/74557164/344478908-f55242f3-cff8-4f81-befd-da68e4df73c6.png?jwt=eyJhbGciOiJIUzI1NiIsInR5cCI6IkpXVCJ9.eyJpc3MiOiJnaXRodWIuY29tIiwiYXVkIjoicmF3LmdpdGh1YnVzZXJjb250ZW50LmNvbSIsImtleSI6ImtleTUiLCJleHAiOjE3MTk3NjQwODUsIm5iZiI6MTcxOTc2Mzc4NSwicGF0aCI6Ii83NDU1NzE2NC8zNDQ0Nzg5MDgtZjU1MjQyZjMtY2ZmOC00ZjgxLWJlZmQtZGE2OGU0ZGY3M2M2LnBuZz9YLUFtei1BbGdvcml0aG09QVdTNC1ITUFDLVNIQTI1NiZYLUFtei1DcmVkZW50aWFsPUFLSUFWQ09EWUxTQTUzUFFLNFpBJTJGMjAyNDA2MzAlMkZ1cy1lYXN0LTElMkZzMyUyRmF3czRfcmVxdWVzdCZYLUFtei1EYXRlPTIwMjQwNjMwVDE2MDk0NVomWC1BbXotRXhwaXJlcz0zMDAmWC1BbXotU2lnbmF0dXJlPTkxYjlmYTkwODFiZmMyY2NjMjVjMWZhNjk1NDZhYjUzOTM1YWUzNjI3ZDljZTQ3NmYzM2I4M2JmNzg5ZGY5MmMmWC1BbXotU2lnbmVkSGVhZGVycz1ob3N0JmFjdG9yX2lkPTAma2V5X2lkPTAmcmVwb19pZD0wIn0.48sEOYbBONNEA-0qYevB7z_NleKW_zL-hNSefu5UYaQ)
240+
241+
### 4. Using 3d Gimbal
242+
243+
The Iris model is equipped with a 3d gimbal and camera that can be controlled directly in MAVProxy using the RC overrides.
244+
245+
#### Run Gazebo
246+
247+
```bash
248+
gz sim -v4 -r iris_runway.sdf
249+
```
250+
251+
#### Run ArduPilot SITL with a specified parameter file
252+
253+
```bash
254+
cd ardupilot
255+
256+
sim_vehicle.py -D -v ArduCopter -f JSON --add-param-file=$HOME/ardupilot_gazebo/config/gazebo-iris-gimbal.parm --console --map
257+
```
258+
259+
Control action for gimbal over RC channel:
260+
261+
| Action | Channel | RC Low | RC High |
262+
| ------------- | ------------- | ------------- | ------------- |
263+
| Roll | RC6 | Roll Left | Roll Right |
264+
| Pitch | RC7 | Pitch Down | Pitch Up |
265+
| Yaw | RC8 | Yaw Left | Yaw Right |
266+
267+
Example usage:
268+
269+
`rc 6 1000` - Gimbal rolls left
270+
271+
`rc 7 2000` - Gimbal pitch upwards
272+
273+
`rc 8 1500` - Gimbal yaw neutral
274+
235275
## Models
236276

237277
In addition to the Iris and Zephyr models included here, a selection

Diff for: config/gazebo-iris-gimbal.parm

+11-7
Original file line numberDiff line numberDiff line change
@@ -14,17 +14,21 @@ RNGFND1_SCALING 10
1414
RNGFND1_PIN 0
1515
RNGFND1_MAX_CM 5000
1616

17-
# Gimbal on mount 1 has 2 DOF
17+
# Gimbal on mount 1 has 3 DOF
1818
MNT1_PITCH_MAX 90
1919
MNT1_PITCH_MIN -90
2020
MNT1_ROLL_MAX 90
2121
MNT1_ROLL_MIN -90
22+
MNT1_YAW_MAX 90
23+
MNT1_YAW_MIN -90
2224
MNT1_TYPE 1
2325

24-
# Gimbal roll and pitch RC
25-
RC9_OPTION 212
26-
RC10_OPTION 213
26+
# Gimbal roll, pitch and yaw RC
27+
RC6_OPTION 212
28+
RC7_OPTION 213
29+
RC8_OPTION 214
2730

28-
# Gimbal roll and pitch servos
29-
SERVO5_FUNCTION 8
30-
SERVO6_FUNCTION 7
31+
# Gimbal roll, pitch and yaw servos
32+
SERVO9_FUNCTION 8
33+
SERVO10_FUNCTION 7
34+
SERVO11_FUNCTION 6

0 commit comments

Comments
 (0)