Rover: support MAV_CMD_DO_SET_CAM_TRIGG_DIST
This commit is contained in:
parent
3b9566bc09
commit
5acc372f40
@ -1260,6 +1260,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
param2 = tell_command.alt;
|
||||
param1 = tell_command.p1;
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
param1 = tell_command.alt;
|
||||
break;
|
||||
}
|
||||
|
||||
mavlink_msg_mission_item_send(chan,msg->sysid,
|
||||
@ -1538,6 +1542,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
tell_command.p1 = packet.param1;
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
tell_command.alt = packet.param1;
|
||||
break;
|
||||
|
||||
default:
|
||||
result = MAV_MISSION_UNSUPPORTED;
|
||||
break;
|
||||
|
@ -92,6 +92,10 @@ static void handle_process_do_command()
|
||||
case MAV_CMD_DO_DIGICAM_CONTROL: // Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty|
|
||||
do_take_picture();
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
camera.set_trigger_distance(next_nonnav_command.alt);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if MOUNT == ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user