Rover: Add MAV_CMD_DO_SET_CAM_TRIGG_DIST support.

This commit is contained in:
Paulo Neves 2017-05-22 18:50:52 +02:00 committed by Randy Mackay
parent 971c8d5948
commit 74d67f8d05

View File

@ -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