Copter: Support do_digicam_x via command_long
This commit is contained in:
parent
bc06d67645
commit
30ed2508d6
@ -1263,6 +1263,30 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
case MAV_CMD_DO_DIGICAM_CONFIGURE:
|
||||
copter.camera.configure(packet.param1,
|
||||
packet.param2,
|
||||
packet.param3,
|
||||
packet.param4,
|
||||
packet.param5,
|
||||
packet.param6,
|
||||
packet.param7);
|
||||
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_DIGICAM_CONTROL:
|
||||
copter.camera.control(packet.param1,
|
||||
packet.param2,
|
||||
packet.param3,
|
||||
packet.param4,
|
||||
packet.param5,
|
||||
packet.param6);
|
||||
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
#endif // CAMERA == ENABLED
|
||||
case MAV_CMD_DO_MOUNT_CONTROL:
|
||||
#if MOUNT == ENABLED
|
||||
copter.camera_mount.control(packet.param1, packet.param2, packet.param3, (MAV_MOUNT_MODE) packet.param7);
|
||||
@ -1724,9 +1748,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
#endif
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
//deprecated. Use MAV_CMD_DO_DIGICAM_CONFIGURE
|
||||
case MAVLINK_MSG_ID_DIGICAM_CONFIGURE: // MAV ID: 202
|
||||
break;
|
||||
|
||||
//deprecated. Use MAV_CMD_DO_DIGICAM_CONTROL
|
||||
case MAVLINK_MSG_ID_DIGICAM_CONTROL:
|
||||
copter.camera.control_msg(msg);
|
||||
copter.log_picture();
|
||||
|
@ -859,7 +859,13 @@ void Copter::do_roi(const AP_Mission::Mission_Command& cmd)
|
||||
void Copter::do_digicam_configure(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
#if CAMERA == ENABLED
|
||||
camera.configure_cmd(cmd);
|
||||
camera.configure(cmd.content.digicam_configure.shooting_mode,
|
||||
cmd.content.digicam_configure.shutter_speed,
|
||||
cmd.content.digicam_configure.aperture,
|
||||
cmd.content.digicam_configure.ISO,
|
||||
cmd.content.digicam_configure.exposure_type,
|
||||
cmd.content.digicam_configure.cmd_id,
|
||||
cmd.content.digicam_configure.engine_cutoff_time);
|
||||
#endif
|
||||
}
|
||||
|
||||
@ -867,7 +873,12 @@ void Copter::do_digicam_configure(const AP_Mission::Mission_Command& cmd)
|
||||
void Copter::do_digicam_control(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
#if CAMERA == ENABLED
|
||||
camera.control_cmd(cmd);
|
||||
camera.control(cmd.content.digicam_control.session,
|
||||
cmd.content.digicam_control.zoom_pos,
|
||||
cmd.content.digicam_control.zoom_step,
|
||||
cmd.content.digicam_control.focus_lock,
|
||||
cmd.content.digicam_control.shooting_cmd,
|
||||
cmd.content.digicam_control.cmd_id);
|
||||
log_picture();
|
||||
#endif
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user