mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 11:07:36 +08:00
camera_trigger: add TRIG_INTERFACE=3 for Mavlink forwarding
This commit is contained in:
@@ -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
|
||||
*
|
||||
|
||||
Reference in New Issue
Block a user