Camera: trigger_pic sends do-digicam-control to components

This (optionally) allows pictures triggered from ch7/ch8
switch to send a mavlink do-digicam-control message to
components
This commit is contained in:
Randy Mackay 2015-03-28 18:36:43 -07:00
parent 1f705eb6a3
commit 8dcd555037
2 changed files with 20 additions and 3 deletions

View File

@ -74,8 +74,9 @@ 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()
AP_Camera::trigger_pic(bool send_mavlink_msg)
{
_image_index++;
switch (_trigger_type)
@ -87,6 +88,20 @@ AP_Camera::trigger_pic()
relay_pic(); // basic relay activation
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;
// 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);
}
}
/// de-activate the trigger after some delay, but without using a delay() function
@ -150,7 +165,7 @@ AP_Camera::control_msg(mavlink_message_t* msg)
*/
if (packet.shot)
{
trigger_pic();
trigger_pic(false);
}
}

View File

@ -9,6 +9,7 @@
#include <AP_Param.h>
#include <AP_Common.h>
#include <GCS_MAVLink.h>
#include <GCS.h>
#include <AP_Relay.h>
#include <AP_GPS.h>
#include <AP_AHRS.h>
@ -39,7 +40,8 @@ public:
}
// single entry point to take pictures
void trigger_pic();
// set send_mavlink_msg to true to send DO_DIGICAM_CONTROL message to all components
void trigger_pic(bool send_mavlink_msg);
// de-activate the trigger after some delay, but without using a delay() function
// should be called at 50hz from main program