mirror of https://github.com/ArduPilot/ardupilot
Plane: Add MAV_CMD_DO_SET_CAM_TRIGG_DIST support.
This commit is contained in:
parent
9c6a7c170f
commit
a45dd30c1d
|
@ -1168,6 +1168,11 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|||
}
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
plane.camera.set_trigger_distance(packet.param1);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
#endif // CAMERA == ENABLED
|
||||
|
||||
case MAV_CMD_DO_MOUNT_CONTROL:
|
||||
|
|
Loading…
Reference in New Issue