Control camera's over MAVLink (#3178)

Allow to configure the MAVLINK autopilot type to drive e.g. DJI camera's but do not change the default behaviour
This commit is contained in:
Christophe De Wagter
2023-12-08 10:49:02 +01:00
committed by GitHub
parent 2083b5898f
commit 0b8cc6b5f2
3 changed files with 8 additions and 1 deletions

View File

@@ -39,6 +39,7 @@
<!-- <module name="mavlink">
<configure name="MAVLINK_BAUD" value="B115200"/>
<configure name="MAVLINK_PORT" value="UART8"/>
<define name="MAV_AUTOPILOT_ID" value="MAV_AUTOPILOT_ARDUPILOTMEGA"/>
</module> -->
<!-- Log in high speed (Remove for outdoor flights) -->

View File

@@ -5,6 +5,7 @@
<description>Basic MAVLink implementation</description>
<configure name="MAVLINK_PORT" value="UARTx|UDPx|UsbS" description="The port device to use for mavlink (default: UART1)"/>
<configure name="MAVLINK_BAUD" value="B57600" description="Baud rate if MAVLINK_PORT is a UART"/>
<define name="MAV_AUTOPILOT_ID" value="MAV_AUTOPILOT_PPZ|MAV_AUTOPILOT_ARDUPILOTMEGA" description="Some MAVLink GCS/Devices require specific ID's to work. Default is to identify as MAV_AUTOPILOT_PPZ."/>
</doc>
<header>
<file name="mavlink.h"/>

View File

@@ -57,6 +57,11 @@
#include "modules/radio_control/radio_control.h"
#endif
// Change the autopilot identification code: by default identify as PPZ autopilot: alternatively as MAV_AUTOPILOT_ARDUPILOTMEGA
#ifndef MAV_AUTOPILOT_ID
#define MAV_AUTOPILOT_ID MAV_AUTOPILOT_PPZ
#endif
#include "modules/datalink/missionlib/mission_manager.h"
// for UINT16_MAX
@@ -500,7 +505,7 @@ static void mavlink_send_heartbeat(struct transport_tx *trans, struct link_devic
}
mavlink_msg_heartbeat_send(MAVLINK_COMM_0,
mav_type,
MAV_AUTOPILOT_PPZ,
MAV_AUTOPILOT_ID,
mav_mode,
0, // custom_mode
mav_state);