diff --git a/README.md b/README.md index cedda89..b89ca07 100644 --- a/README.md +++ b/README.md @@ -232,6 +232,44 @@ 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 OGC: + +`Open QGC > Application Settings > Video Settings > Select UDP h.264 Video Stream & use port 5600` + +### 4. Using Gimbal + +To control gimbal using RC channels, + +#### 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 3cf5d18..f8b5c3d 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 \ No newline at end of file