From 9390539231dd2f18fa9006dc8d3d1a298ceb2cbe Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 26 Jul 2017 14:32:40 +1000 Subject: [PATCH] AP_Camera: tidy up usage of trigger_pic --- libraries/AP_Camera/AP_Camera.cpp | 36 +++++++++++++++---------------- libraries/AP_Camera/AP_Camera.h | 5 ++--- 2 files changed, 19 insertions(+), 22 deletions(-) diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index 71d53775a9..2e8d70f193 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -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); } /* diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 0c8210aaa3..cfbadc0317 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -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