AP_Camera: tidy up usage of trigger_pic

This commit is contained in:
Peter Barker 2017-07-26 14:32:40 +10:00 committed by Francisco Ferreira
parent b299772a75
commit 9390539231
2 changed files with 19 additions and 22 deletions

View File

@ -128,8 +128,7 @@ AP_Camera::relay_pic()
/// single entry point to take pictures
/// set send_mavlink_msg to true to send DO_DIGICAM_CONTROL message to all components
void
AP_Camera::trigger_pic(bool send_mavlink_msg)
void AP_Camera::trigger_pic()
{
setup_feedback_callback();
@ -144,19 +143,7 @@ AP_Camera::trigger_pic(bool send_mavlink_msg)
break;
}
if (send_mavlink_msg) {
// create command long mavlink message
mavlink_command_long_t cmd_msg;
memset(&cmd_msg, 0, sizeof(cmd_msg));
cmd_msg.command = MAV_CMD_DO_DIGICAM_CONTROL;
cmd_msg.param5 = 1;
// create message
mavlink_message_t msg;
mavlink_msg_command_long_encode(0, 0, &msg, &cmd_msg);
// forward to all components
GCS_MAVLINK::send_to_components(&msg);
}
log_picture();
}
/// de-activate the trigger after some delay, but without using a delay() function
@ -221,8 +208,7 @@ void AP_Camera::control(float session, float zoom_pos, float zoom_step, float fo
{
// take picture
if (is_equal(shooting_cmd,1.0f)) {
trigger_pic(false);
log_picture();
trigger_pic();
}
mavlink_message_t msg;
@ -420,8 +406,20 @@ void AP_Camera::log_picture()
// take_picture - take a picture
void AP_Camera::take_picture()
{
trigger_pic(true);
log_picture();
// take a local picture:
trigger_pic();
// tell all of our components to take a picture:
mavlink_command_long_t cmd_msg;
memset(&cmd_msg, 0, sizeof(cmd_msg));
cmd_msg.command = MAV_CMD_DO_DIGICAM_CONTROL;
cmd_msg.param5 = 1;
// create message
mavlink_message_t msg;
mavlink_msg_command_long_encode(0, 0, &msg, &cmd_msg);
// forward to all components
GCS_MAVLINK::send_to_components(&msg);
}
/*

View File

@ -108,9 +108,8 @@ private:
const AP_GPS &gps;
const AP_AHRS &ahrs;
// single entry point to take pictures
// set send_mavlink_msg to true to send DO_DIGICAM_CONTROL message to all components
void trigger_pic(bool send_mavlink_msg);
// entry point to trip local shutter (e.g. by relay or servo)
void trigger_pic();
// de-activate the trigger after some delay, but without using a delay() function
// should be called at 50hz from main program