Plane: add call to send digicam configure messages from a mission item
Also add log_picture to separate the taking of a picture from the dataflash logging and feedback to GCS
This commit is contained in:
parent
337a94e52e
commit
ab1cf2261d
@ -1544,7 +1544,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
|
||||
case MAVLINK_MSG_ID_DIGICAM_CONTROL:
|
||||
{
|
||||
do_take_picture();
|
||||
camera.control_msg(msg);
|
||||
log_picture();
|
||||
break;
|
||||
}
|
||||
#endif // CAMERA == ENABLED
|
||||
|
@ -14,6 +14,10 @@ static void do_change_speed(const AP_Mission::Mission_Command& cmd);
|
||||
static void do_set_home(const AP_Mission::Mission_Command& cmd);
|
||||
static void do_continue_and_change_alt(const AP_Mission::Mission_Command& cmd);
|
||||
static bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);
|
||||
#if CAMERA == ENABLED
|
||||
static void do_digicam_configure(const AP_Mission::Mission_Command& cmd);
|
||||
static void do_digicam_control(const AP_Mission::Mission_Command& cmd);
|
||||
#endif
|
||||
|
||||
|
||||
/********************************************************************************/
|
||||
@ -152,10 +156,12 @@ start_command(const AP_Mission::Mission_Command& cmd)
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_DIGICAM_CONFIGURE: // Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)|
|
||||
do_digicam_configure(cmd);
|
||||
break;
|
||||
|
||||
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();
|
||||
// do_digicam_control Send Digicam Control message with the camera library
|
||||
do_digicam_control(cmd);
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
@ -650,16 +656,39 @@ static void do_set_home(const AP_Mission::Mission_Command& cmd)
|
||||
}
|
||||
}
|
||||
|
||||
// do_digicam_configure Send Digicam Configure message with the camera library
|
||||
static void do_digicam_configure(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
#if CAMERA == ENABLED
|
||||
camera.configure_cmd(cmd);
|
||||
#endif
|
||||
}
|
||||
|
||||
// do_digicam_control Send Digicam Control message with the camera library
|
||||
static void do_digicam_control(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
#if CAMERA == ENABLED
|
||||
camera.control_cmd(cmd);
|
||||
log_picture();
|
||||
#endif
|
||||
}
|
||||
|
||||
// do_take_picture - take a picture with the camera library
|
||||
static void do_take_picture()
|
||||
{
|
||||
#if CAMERA == ENABLED
|
||||
camera.trigger_pic();
|
||||
camera.trigger_pic(true);
|
||||
log_picture();
|
||||
#endif
|
||||
}
|
||||
|
||||
// log_picture - log picture taken and send feedback to GCS
|
||||
static void log_picture()
|
||||
{
|
||||
gcs_send_message(MSG_CAMERA_FEEDBACK);
|
||||
if (should_log(MASK_LOG_CAMERA)) {
|
||||
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// start_command_callback - callback function called from ap-mission when it begins a new mission command
|
||||
|
Loading…
Reference in New Issue
Block a user