camera_trigger: add TRIG_INTERFACE=3 for Mavlink forwarding

This commit is contained in:
Beat Küng
2017-02-06 14:52:23 +01:00
parent 212502b2b1
commit 507e3b0263
3 changed files with 25 additions and 1 deletions
@@ -76,7 +76,8 @@ extern "C" __EXPORT int camera_trigger_main(int argc, char *argv[]);
typedef enum : int32_t {
CAMERA_INTERFACE_MODE_NONE = 0,
CAMERA_INTERFACE_MODE_RELAY,
CAMERA_INTERFACE_MODE_SEAGULL_MAP2_PWM
CAMERA_INTERFACE_MODE_SEAGULL_MAP2_PWM,
CAMERA_INTERFACE_MODE_MAVLINK
} camera_interface_mode_t;
class CameraTrigger
@@ -265,6 +266,11 @@ CameraTrigger::CameraTrigger() :
#endif
case CAMERA_INTERFACE_MODE_MAVLINK:
/* start an interface that does nothing. Instead mavlink will listen to the camera_trigger uORB message */
_camera_interface = new CameraInterface();
break;
default:
PX4_ERR("unknown camera interface mode: %i", (int)_camera_interface_mode);
break;
@@ -46,6 +46,7 @@
*
* @value 1 GPIO
* @value 2 Seagull MAP2 (PWM)
* @value 3 MAVLink (forward via MAV_CMD_IMAGE_START_CAPTURE)
*
* @reboot_required true
*
+17
View File
@@ -1420,6 +1420,23 @@ protected:
/* ensure that only active trigger events are sent */
if (trigger.timestamp > 0) {
mavlink_msg_camera_trigger_send_struct(_mavlink->get_channel(), &msg);
/* send MAV_CMD_IMAGE_START_CAPTURE */
mavlink_command_long_t msg_cmd;
msg_cmd.target_system = mavlink_system.sysid;
msg_cmd.target_component = MAV_COMP_ID_CAMERA;
msg_cmd.command = MAV_CMD_IMAGE_START_CAPTURE;
msg_cmd.confirmation = 0;
msg_cmd.param1 = 0;
msg_cmd.param2 = 1;
msg_cmd.param3 = 0;
msg_cmd.param4 = NAN;
msg_cmd.param5 = NAN;
msg_cmd.param6 = NAN;
msg_cmd.param7 = NAN;
mavlink_msg_command_long_send_struct(_mavlink->get_channel(), &msg_cmd);
}
}
}