mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
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;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||||
|
plane.camera.set_trigger_distance(packet.param1);
|
||||||
|
result = MAV_RESULT_ACCEPTED;
|
||||||
|
break;
|
||||||
#endif // CAMERA == ENABLED
|
#endif // CAMERA == ENABLED
|
||||||
|
|
||||||
case MAV_CMD_DO_MOUNT_CONTROL:
|
case MAV_CMD_DO_MOUNT_CONTROL:
|
||||||
|
Loading…
Reference in New Issue
Block a user