Copter: support MAV_CMD_DO_SET_CAM_TRIGG_DIST

This commit is contained in:
Andrew Tridgell 2013-10-11 21:34:23 +11:00
parent 0ec322ee47
commit 3b9566bc09
2 changed files with 13 additions and 0 deletions

View File

@ -1406,6 +1406,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,
@ -1707,6 +1711,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
tell_command.alt = packet.param2;
tell_command.p1 = packet.param1;
break;
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
// use alt so we can support 32 bit values
tell_command.alt = packet.param1;
break;
}
if(packet.current == 2) { //current = 2 is a flag to tell us this is a "guided mode" waypoint and not for the mission

View File

@ -117,6 +117,10 @@ static void process_now_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(command_cond_queue.alt);
break;
#endif
#if MOUNT == ENABLED