diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 5391fe13f4..2ca8f3d5ef 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -859,7 +859,12 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) } result = MAV_RESULT_ACCEPTED; break; -#endif // CAMERA == ENABLED + + case MAV_CMD_DO_SET_CAM_TRIGG_DIST: + rover.camera.set_trigger_distance(packet.param1); + result = MAV_RESULT_ACCEPTED; + break; +#endif // CAMERA == ENABLED case MAV_CMD_DO_MOUNT_CONTROL: #if MOUNT == ENABLED