From f7c02854b8324932296a445650cd106fece4df5a Mon Sep 17 00:00:00 2001 From: Sayshara Date: Fri, 1 Aug 2025 15:38:04 +0200 Subject: [PATCH 1/3] add: Battery_Status_V2 stream --- src/modules/mavlink/mavlink_main.cpp | 3 + src/modules/mavlink/mavlink_messages.cpp | 6 + .../mavlink/streams/BATTERY_STATUS_V2.hpp | 137 ++++++++++++++++++ 3 files changed, 146 insertions(+) create mode 100644 src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index fe3703e5d60d..1721dc5ae32c 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1428,6 +1428,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("ATTITUDE_TARGET", 2.0f); configure_stream_local("AVAILABLE_MODES", 0.3f); configure_stream_local("BATTERY_STATUS", 0.5f); + configure_stream_local("BATTERY_STATUS_V2", 0.5f); configure_stream_local("CAMERA_IMAGE_CAPTURED", unlimited_rate); configure_stream_local("CURRENT_MODE", 0.5f); configure_stream_local("DISTANCE_SENSOR", 0.5f); @@ -1504,6 +1505,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("ATTITUDE_TARGET", 10.0f); configure_stream_local("AVAILABLE_MODES", 0.3f); configure_stream_local("BATTERY_STATUS", 0.5f); + configure_stream_local("BATTERY_STATUS_V2", 0.5f); configure_stream_local("CAMERA_IMAGE_CAPTURED", unlimited_rate); configure_stream_local("CURRENT_MODE", 0.5f); configure_stream_local("EFI_STATUS", 2.0f); @@ -1665,6 +1667,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("ATTITUDE_TARGET", 8.0f); configure_stream_local("AVAILABLE_MODES", 0.3f); configure_stream_local("BATTERY_STATUS", 0.5f); + configure_stream_local("BATTERY_STATUS_V2", 0.5f); configure_stream_local("CAMERA_IMAGE_CAPTURED", unlimited_rate); configure_stream_local("CURRENT_MODE", 0.5f); configure_stream_local("EFI_STATUS", 10.0f); diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 876d4c58258d..c994d9989563 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -63,6 +63,7 @@ #include "streams/ATTITUDE_TARGET.hpp" #include "streams/AUTOPILOT_VERSION.hpp" #include "streams/BATTERY_STATUS.hpp" +#include "streams/BATTERY_STATUS_V2.hpp" #include "streams/CAMERA_IMAGE_CAPTURED.hpp" #include "streams/CAMERA_TRIGGER.hpp" #include "streams/COMMAND_LONG.hpp" @@ -262,7 +263,12 @@ static const StreamListItem streams_list[] = { #if defined(SYS_STATUS_HPP) create_stream_list_item(), #endif // SYS_STATUS_HPP +#if defined(BATTERY_STATUS_HPP) create_stream_list_item(), +#endif // BATTERY_STATUS_HPP +#if defined(BATTERY_STATUS_V2_HPP) + create_stream_list_item(), +#endif // BATTERY_STATUS_V2_HPP #if defined(BATTERY_INFO_HPP) create_stream_list_item(), #endif // BATTERY_INFO_HPP diff --git a/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp b/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp new file mode 100644 index 000000000000..5e8bf7a641b4 --- /dev/null +++ b/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp @@ -0,0 +1,137 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef BATTERY_STATUS_V2_HPP +#define BATTERY_STATUS_V2_HPP + +#include + +class MavlinkStreamBatteryStatusV2 : public MavlinkStream +{ +public: + static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamBatteryStatusV2(mavlink); } + + static constexpr const char *get_name_static() { return "BATTERY_STATUS_V2"; } + static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_BATTERY_STATUS_V2; } + + const char *get_name() const override { return get_name_static(); } + uint16_t get_id() override { return get_id_static(); } + + unsigned get_size() override + { + static constexpr unsigned size_per_battery = MAVLINK_MSG_ID_BATTERY_STATUS_V2_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + return size_per_battery * _battery_status_subs.advertised_count(); + } + +private: + explicit MavlinkStreamBatteryStatusV2(Mavlink *mavlink) : MavlinkStream(mavlink) {} + + uORB::SubscriptionMultiArray _battery_status_subs{ORB_ID::battery_status}; + + bool send() override + { + bool updated = false; + + for (auto &battery_sub : _battery_status_subs) { + battery_status_s battery_status; + + if (battery_sub.update(&battery_status)) { + mavlink_battery_status_v2_t bat_msg{}; + + bat_msg.id = battery_status.id; + bat_msg.temperature = (battery_status.connected && PX4_ISFINITE(battery_status.temperature)) ? + static_cast(battery_status.temperature * 1e2f) : INT16_MAX; + bat_msg.voltage = (battery_status.connected + && PX4_ISFINITE(battery_status.voltage_v)) ? battery_status.voltage_v : float(NAN); + bat_msg.current = (battery_status.connected + && PX4_ISFINITE(battery_status.current_a)) ? battery_status.current_a : float(NAN); + bat_msg.capacity_consumed = (battery_status.connected + && PX4_ISFINITE(battery_status.discharged_mah)) ? battery_status.discharged_mah * 1e-3f : float(NAN); + bat_msg.capacity_remaining = (battery_status.connected && PX4_ISFINITE(battery_status.remaining) + && PX4_ISFINITE(static_cast(battery_status.capacity))) ? + battery_status.remaining * (static_cast(battery_status.capacity) * 1e-3f) : float(NAN); + bat_msg.percent_remaining = (battery_status.connected && PX4_ISFINITE(battery_status.remaining)) ? + static_cast(roundf(battery_status.remaining * 1e2f)) : UINT8_MAX; + + bat_msg.status_flags = get_status_flags(battery_status); + + mavlink_msg_battery_status_v2_send_struct(_mavlink->get_channel(), &bat_msg); + updated = true; + } + } + + return updated; + } + + inline uint32_t get_status_flags(const battery_status_s &battery_status) const + { + uint32_t status_flags = 0; + uint16_t faults = battery_status.faults; + + if (battery_status.warning == battery_status_s::STATE_UNHEALTHY) { + status_flags |= MAV_BATTERY_STATUS_FLAGS_NOT_READY_TO_USE; + } + + if (battery_status.warning == battery_status_s::STATE_CHARGING) { + status_flags |= MAV_BATTERY_STATUS_FLAGS_CHARGING; + } + + if (faults & battery_status_s::FAULT_HARDWARE_FAILURE) { + status_flags |= MAV_BATTERY_STATUS_FLAGS_REQUIRES_SERVICE | MAV_BATTERY_STATUS_FLAGS_BAD_BATTERY; + } + + if (faults & battery_status_s::FAULT_OVER_TEMPERATURE) { + status_flags |= MAV_BATTERY_STATUS_FLAGS_FAULT_OVER_TEMPERATURE; + } + + if (faults & battery_status_s::FAULT_UNDER_TEMPERATURE) { + status_flags |= MAV_BATTERY_STATUS_FLAGS_FAULT_UNDER_TEMPERATURE; + } + + if (faults & battery_status_s::FAULT_OVER_CURRENT) { + status_flags |= MAV_BATTERY_STATUS_FLAGS_FAULT_OVER_CURRENT; + } + + if (faults & battery_status_s::FAULT_INCOMPATIBLE_VOLTAGE) { + status_flags |= MAV_BATTERY_STATUS_FLAGS_FAULT_INCOMPATIBLE_VOLTAGE; + } + + if (faults & battery_status_s::FAULT_INCOMPATIBLE_FIRMWARE) { + status_flags |= MAV_BATTERY_STATUS_FLAGS_FAULT_INCOMPATIBLE_FIRMWARE; + } + + return status_flags; + } +}; + +#endif // BATTERY_STATUS_V2_HPP From f066884fab105f2e80bd392a309146744a66ea6a Mon Sep 17 00:00:00 2001 From: Sayshara Date: Thu, 7 Aug 2025 23:31:10 +0200 Subject: [PATCH 2/3] fix: handle invalid battery values as suggested (refs #25347) --- .../mavlink/streams/BATTERY_STATUS_V2.hpp | 17 +++++++++++------ 1 file changed, 11 insertions(+), 6 deletions(-) diff --git a/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp b/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp index 5e8bf7a641b4..c2025dddf954 100644 --- a/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp +++ b/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp @@ -69,18 +69,23 @@ class MavlinkStreamBatteryStatusV2 : public MavlinkStream mavlink_battery_status_v2_t bat_msg{}; bat_msg.id = battery_status.id; - bat_msg.temperature = (battery_status.connected && PX4_ISFINITE(battery_status.temperature)) ? - static_cast(battery_status.temperature * 1e2f) : INT16_MAX; + bat_msg.temperature = (battery_status.connected + && PX4_ISFINITE(battery_status.temperature)) ? static_cast(battery_status.temperature * 1e2f) : INT16_MAX; bat_msg.voltage = (battery_status.connected - && PX4_ISFINITE(battery_status.voltage_v)) ? battery_status.voltage_v : float(NAN); + && PX4_ISFINITE(battery_status.voltage_v) + && battery_status.voltage_v != 0.0f) ? battery_status.voltage_v : float(NAN); bat_msg.current = (battery_status.connected - && PX4_ISFINITE(battery_status.current_a)) ? battery_status.current_a : float(NAN); + && PX4_ISFINITE(battery_status.current_a) + && battery_status.current_a != -1.0f) ? battery_status.current_a : float(NAN); bat_msg.capacity_consumed = (battery_status.connected - && PX4_ISFINITE(battery_status.discharged_mah)) ? battery_status.discharged_mah * 1e-3f : float(NAN); + && PX4_ISFINITE(battery_status.discharged_mah) + && battery_status.discharged_mah != -1.0) ? battery_status.discharged_mah * 1e-3f : float(NAN); bat_msg.capacity_remaining = (battery_status.connected && PX4_ISFINITE(battery_status.remaining) + && battery_status.remaining != -1.0f && PX4_ISFINITE(static_cast(battery_status.capacity))) ? battery_status.remaining * (static_cast(battery_status.capacity) * 1e-3f) : float(NAN); - bat_msg.percent_remaining = (battery_status.connected && PX4_ISFINITE(battery_status.remaining)) ? + bat_msg.percent_remaining = (battery_status.connected && PX4_ISFINITE(battery_status.remaining) + && battery_status.remaining != -1.0f) ? static_cast(roundf(battery_status.remaining * 1e2f)) : UINT8_MAX; bat_msg.status_flags = get_status_flags(battery_status); From 3d8f1982ee34e97f1354f06314728035c74025d6 Mon Sep 17 00:00:00 2001 From: Sayshara Date: Fri, 8 Aug 2025 00:13:01 +0200 Subject: [PATCH 3/3] fix: capacity_remaining calculation, float comparison (refs #25347) --- .../mavlink/streams/BATTERY_STATUS_V2.hpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp b/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp index c2025dddf954..76b950200d1a 100644 --- a/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp +++ b/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp @@ -73,19 +73,19 @@ class MavlinkStreamBatteryStatusV2 : public MavlinkStream && PX4_ISFINITE(battery_status.temperature)) ? static_cast(battery_status.temperature * 1e2f) : INT16_MAX; bat_msg.voltage = (battery_status.connected && PX4_ISFINITE(battery_status.voltage_v) - && battery_status.voltage_v != 0.0f) ? battery_status.voltage_v : float(NAN); + && !math::isZero(battery_status.voltage_v)) ? battery_status.voltage_v : float(NAN); bat_msg.current = (battery_status.connected && PX4_ISFINITE(battery_status.current_a) - && battery_status.current_a != -1.0f) ? battery_status.current_a : float(NAN); + && fabsf(battery_status.current_a - (-1.0f)) > FLT_EPSILON) ? battery_status.current_a : float(NAN); bat_msg.capacity_consumed = (battery_status.connected && PX4_ISFINITE(battery_status.discharged_mah) - && battery_status.discharged_mah != -1.0) ? battery_status.discharged_mah * 1e-3f : float(NAN); - bat_msg.capacity_remaining = (battery_status.connected && PX4_ISFINITE(battery_status.remaining) - && battery_status.remaining != -1.0f - && PX4_ISFINITE(static_cast(battery_status.capacity))) ? - battery_status.remaining * (static_cast(battery_status.capacity) * 1e-3f) : float(NAN); + && fabsf(battery_status.discharged_mah - (-1.0f)) > FLT_EPSILON) ? battery_status.discharged_mah * 1e-3f : float(NAN); + bat_msg.capacity_remaining = (battery_status.connected && PX4_ISFINITE(battery_status.remaining_capacity_wh) + && PX4_ISFINITE(battery_status.nominal_voltage) + && !math::isZero(battery_status.nominal_voltage)) ? + battery_status.remaining_capacity_wh / battery_status.nominal_voltage : float(NAN); bat_msg.percent_remaining = (battery_status.connected && PX4_ISFINITE(battery_status.remaining) - && battery_status.remaining != -1.0f) ? + && fabsf(battery_status.remaining - (-1.0f)) > FLT_EPSILON) ? static_cast(roundf(battery_status.remaining * 1e2f)) : UINT8_MAX; bat_msg.status_flags = get_status_flags(battery_status);