mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Copter: Add MAV_CMD_DO_SET_CAM_TRIGG_DIST support
This commit is contained in:
parent
74d67f8d05
commit
9c6a7c170f
@ -1224,6 +1224,12 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
||||
}
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
copter.camera.set_trigger_distance(packet.param1);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
#endif // CAMERA == ENABLED
|
||||
case MAV_CMD_DO_MOUNT_CONTROL:
|
||||
#if MOUNT == ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user