From 8f49cdd64643e8b335b4b15b3a5e0eb5f8a86780 Mon Sep 17 00:00:00 2001 From: olliw42 Date: Sat, 21 Sep 2024 17:50:12 +0200 Subject: [PATCH] update bp_mavlink, incoude two CAN PRs --- bp_mavlink/ardupilotmega.xml | 5 ++++- bp_mavlink/common.xml | 20 ++++++++++++++++++++ libraries/AP_CANManager/AP_CANManager.cpp | 6 ++++++ libraries/AP_DroneCAN/AP_DroneCAN.h | 11 +++++++++-- libraries/bp_version.h | 9 +++++++-- 5 files changed, 46 insertions(+), 5 deletions(-) diff --git a/bp_mavlink/ardupilotmega.xml b/bp_mavlink/ardupilotmega.xml index 6501a7d0df76d..0430986a199a7 100644 --- a/bp_mavlink/ardupilotmega.xml +++ b/bp_mavlink/ardupilotmega.xml @@ -314,7 +314,7 @@ Change target altitude at a given rate. This slews the vehicle at a controllable rate between it's previous altitude and the new one. (affects GUIDED only. Outside GUIDED, aircraft ignores these commands. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.) Empty Empty - Rate of change, toward new altitude. 0 for maximum rate change. Positive numbers only, as negative numbers will not converge on the new target alt. + Rate of change, toward new altitude. 0 for maximum rate change. Positive numbers only, as negative numbers will not converge on the new target alt. Empty Empty Empty @@ -998,6 +998,9 @@ Set if EKF's predicted horizontal position (absolute) estimate is good. + + Set if EKF believes the GPS input data is faulty. + Set if EKF has never been healthy. diff --git a/bp_mavlink/common.xml b/bp_mavlink/common.xml index 3ad86bafb0530..bbecbdf64853e 100644 --- a/bp_mavlink/common.xml +++ b/bp_mavlink/common.xml @@ -3310,6 +3310,9 @@ Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS). + + Camera supports absolute thermal range (request CAMERA_THERMAL_RANGE with MAV_CMD_REQUEST_MESSAGE) (WIP). + Stream status flags (Bitmap) @@ -3319,6 +3322,9 @@ Stream is thermal imaging + + Stream can report absolute thermal range (see CAMERA_THERMAL_RANGE). (WIP). + Video stream types @@ -6105,6 +6111,20 @@ Heading in radians, in NED. NAN if unknown Accuracy of heading, in NED. NAN if unknown + + + + Camera absolute thermal range. This can be streamed when the associated `VIDEO_STREAM_STATUS.flag` bit `VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED` is set, but a GCS may choose to only request it for the current active stream. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval (param3 indicates the stream id of the current camera, or 0 for all streams, param4 indicates the target camera_device_id for autopilot-attached cameras or 0 for MAVLink cameras). + Timestamp (time since system boot). + Video Stream ID (1 for first, 2 for second, etc.) + Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). + Temperature max. + Temperature max point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown. + Temperature max point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown. + Temperature min. + Temperature min point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown. + Temperature min point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown. + Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE. Timestamp (time since system boot). diff --git a/libraries/AP_CANManager/AP_CANManager.cpp b/libraries/AP_CANManager/AP_CANManager.cpp index a8e7c7e9a3892..563f8fbb032a7 100644 --- a/libraries/AP_CANManager/AP_CANManager.cpp +++ b/libraries/AP_CANManager/AP_CANManager.cpp @@ -430,6 +430,8 @@ bool AP_CANManager::handle_can_forward(mavlink_channel_t chan, const mavlink_com for (auto can_iface : hal.can) { if (can_iface && can_forward.callback_id != 0) { can_iface->unregister_frame_callback(can_forward.callback_id); +//OW https://github.com/ArduPilot/ardupilot/pull/28182 + can_forward.callback_id = 0; } } return true; @@ -451,6 +453,8 @@ bool AP_CANManager::handle_can_forward(mavlink_channel_t chan, const mavlink_com for (uint8_t i=0; iunregister_frame_callback(can_forward.callback_id); +//OW https://github.com/ArduPilot/ardupilot/pull/28182 + can_forward.callback_id = 0; } } @@ -647,6 +651,8 @@ void AP_CANManager::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &fram if (can_forward.callback_id != 0 && AP_HAL::millis() - can_forward.last_callback_enable_ms > 5000) { hal.can[bus]->unregister_frame_callback(can_forward.callback_id); +//OW https://github.com/ArduPilot/ardupilot/pull/28182 + can_forward.callback_id = 0; return; } can_forward.frame_counter = 0; diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.h b/libraries/AP_DroneCAN/AP_DroneCAN.h index e1b713d33f1ad..0be79e170d215 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN.h @@ -235,10 +235,16 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { uint32_t *mem_pool; - AP_DroneCAN_DNA_Server _dna_server; +//OW https://github.com/ArduPilot/ardupilot/pull/28157 +// AP_DroneCAN_DNA_Server _dna_server; uint8_t _driver_index; +//OW https://github.com/ArduPilot/ardupilot/pull/28157 + CanardInterface canard_iface; + + AP_DroneCAN_DNA_Server _dna_server; + char _thread_name[13]; bool _initialized; ///// SRV output ///// @@ -292,7 +298,8 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { } _relay; #endif - CanardInterface canard_iface; +//OW https://github.com/ArduPilot/ardupilot/pull/28157 +// CanardInterface canard_iface; #if AP_DRONECAN_SERIAL_ENABLED AP_DroneCAN_Serial serial; diff --git a/libraries/bp_version.h b/libraries/bp_version.h index aa13fa7047c57..4f2aee371683b 100644 --- a/libraries/bp_version.h +++ b/libraries/bp_version.h @@ -1,7 +1,7 @@ #pragma once -#define BETAPILOTVERSION "v060i" -#define DATEOFBASEBRANCH "20240903" +#define BETAPILOTVERSION "v060j" +#define DATEOFBASEBRANCH "20240921" /* search for //OW to find all changes THR_MINSPD THR_SLEW SUPP_MAN waiting for rudder release @@ -11,6 +11,11 @@ on-top features: - RC_Channel, AUX_FUNC: CAMERA_SET_MODE, CAMERA_TRIG_MODE (eq CAM_MODE_TOGGLE) (OW CAMERA) - Plane THR (OW THR_SUPP) +includes +- https://github.com/ArduPilot/ardupilot/pull/28182 +- https://github.com/ArduPilot/ardupilot/pull/28157 + + remove zflags, not used, could use now options remove GCS_serial_control: SERIAL_CONTROL 8E1 2024.09.03: v060