forked from Archive/PX4-Autopilot
SMART_BATTERY_INFO to BATTERY_INFO (#22875)
* Update submodule mavlink to latest Wed Mar 13 01:02:16 UTC 2024 - mavlink in PX4/Firmware (497327e916103ef05ff8f08f47d33b9a19bc28d7):c4a5c49737
- mavlink current upstream:a3558d6b33
- Changes:c4a5c49737...a3558d6b33
a3558d6b 2024-03-07 Hamish Willee - common - DO_FENCE_ENABLE/PARACHUTE fix (#2090) b9730e0f 2024-03-06 olliw42 - update RADIO_RC_CHANNELS to latest, remove all mlrs from storm32.xml (#1919) 7fed0268 2024-03-06 Patrick José Pereira - common: MAV_CMD_DO_SET_SYS_CMP_ID: Add first version (#2082) 2909b481 2024-03-06 Hamish Willee - Update Pymavlink (#2089) e9b532a9 2024-03-05 Randy Mackay - common: add set-camera-source command (#2079) bcdbeb7f 2024-03-01 auturgy - Allow individual fences to be enabled and disabled (#2085) 2f8403d1 2024-02-29 Hamish Willee - MAV_CMD_ODID_SET_EMERGENCY - (#2086) daa59c02 2024-02-22 Peter Barker - common.xml: add a command to deal with safety switch (#2081) 977332e2 2024-02-14 Hamish Willee - COMPONENT_INFORMATION_BASIC - add manufacturer date (#2078) 4fef7de2 2024-02-07 Randy Mackay - Common: rename SMART_BATTERY_INFO to BATTERY_INFO and add SOH (#2070) 3865b311 2024-02-01 Hamish Willee - FLIGHT_INFORMATION - description to match PX4 (#2067) f80e6818 2024-01-31 KonradRudin - development.xml: merge both MAV_CMD enums together (#2074) * SMART_BATTERY_INFO to BATTERY_INFO on new mavlink module * Update src/modules/mavlink/streams/BATTERY_INFO.hpp * fix trivial whitespace --------- Co-authored-by: PX4 BuildBot <bot@px4.io> Co-authored-by: Daniel Agar <daniel@agar.ca>
This commit is contained in:
parent
2e6dd243af
commit
95627ea098
|
@ -1 +1 @@
|
||||||
Subproject commit c4a5c497379ca873f73abe691a033641a6a5a817
|
Subproject commit a3558d6b335d930fc01816fd168d16b3f38ed434
|
|
@ -132,6 +132,7 @@
|
||||||
#if !defined(CONSTRAINED_FLASH)
|
#if !defined(CONSTRAINED_FLASH)
|
||||||
# include "streams/ADSB_VEHICLE.hpp"
|
# include "streams/ADSB_VEHICLE.hpp"
|
||||||
# include "streams/AUTOPILOT_STATE_FOR_GIMBAL_DEVICE.hpp"
|
# include "streams/AUTOPILOT_STATE_FOR_GIMBAL_DEVICE.hpp"
|
||||||
|
# include "streams/BATTERY_INFO.hpp"
|
||||||
# include "streams/DEBUG.hpp"
|
# include "streams/DEBUG.hpp"
|
||||||
# include "streams/DEBUG_FLOAT_ARRAY.hpp"
|
# include "streams/DEBUG_FLOAT_ARRAY.hpp"
|
||||||
# include "streams/DEBUG_VECT.hpp"
|
# include "streams/DEBUG_VECT.hpp"
|
||||||
|
@ -147,7 +148,6 @@
|
||||||
# include "streams/ODOMETRY.hpp"
|
# include "streams/ODOMETRY.hpp"
|
||||||
# include "streams/SCALED_PRESSURE2.hpp"
|
# include "streams/SCALED_PRESSURE2.hpp"
|
||||||
# include "streams/SCALED_PRESSURE3.hpp"
|
# include "streams/SCALED_PRESSURE3.hpp"
|
||||||
# include "streams/SMART_BATTERY_INFO.hpp"
|
|
||||||
# include "streams/UAVIONIX_ADSB_OUT_CFG.hpp"
|
# include "streams/UAVIONIX_ADSB_OUT_CFG.hpp"
|
||||||
# include "streams/UAVIONIX_ADSB_OUT_DYNAMIC.hpp"
|
# include "streams/UAVIONIX_ADSB_OUT_DYNAMIC.hpp"
|
||||||
# include "streams/UTM_GLOBAL_POSITION.hpp"
|
# include "streams/UTM_GLOBAL_POSITION.hpp"
|
||||||
|
@ -259,9 +259,9 @@ static const StreamListItem streams_list[] = {
|
||||||
create_stream_list_item<MavlinkStreamSysStatus>(),
|
create_stream_list_item<MavlinkStreamSysStatus>(),
|
||||||
#endif // SYS_STATUS_HPP
|
#endif // SYS_STATUS_HPP
|
||||||
create_stream_list_item<MavlinkStreamBatteryStatus>(),
|
create_stream_list_item<MavlinkStreamBatteryStatus>(),
|
||||||
#if defined(SMART_BATTERY_INFO_HPP)
|
#if defined(BATTERY_INFO_HPP)
|
||||||
create_stream_list_item<MavlinkStreamSmartBatteryInfo>(),
|
create_stream_list_item<MavlinkStreamBatteryInfo>(),
|
||||||
#endif // SMART_BATTERY_INFO_HPP
|
#endif // BATTERY_INFO_HPP
|
||||||
#if defined(HIGHRES_IMU_HPP)
|
#if defined(HIGHRES_IMU_HPP)
|
||||||
create_stream_list_item<MavlinkStreamHighresIMU>(),
|
create_stream_list_item<MavlinkStreamHighresIMU>(),
|
||||||
#endif // HIGHRES_IMU_HPP
|
#endif // HIGHRES_IMU_HPP
|
||||||
|
|
|
@ -31,30 +31,30 @@
|
||||||
*
|
*
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
#ifndef SMART_BATTERY_INFO_HPP
|
#ifndef BATTERY_INFO_HPP
|
||||||
#define SMART_BATTERY_INFO_HPP
|
#define BATTERY_INFO_HPP
|
||||||
|
|
||||||
#include <uORB/topics/battery_status.h>
|
#include <uORB/topics/battery_status.h>
|
||||||
|
|
||||||
class MavlinkStreamSmartBatteryInfo : public MavlinkStream
|
class MavlinkStreamBatteryInfo : public MavlinkStream
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamSmartBatteryInfo(mavlink); }
|
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamBatteryInfo(mavlink); }
|
||||||
|
|
||||||
static constexpr const char *get_name_static() { return "SMART_BATTERY_INFO"; }
|
static constexpr const char *get_name_static() { return "BATTERY_INFO"; }
|
||||||
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_SMART_BATTERY_INFO; }
|
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_BATTERY_INFO; }
|
||||||
|
|
||||||
const char *get_name() const override { return get_name_static(); }
|
const char *get_name() const override { return get_name_static(); }
|
||||||
uint16_t get_id() override { return get_id_static(); }
|
uint16_t get_id() override { return get_id_static(); }
|
||||||
|
|
||||||
unsigned get_size() override
|
unsigned get_size() override
|
||||||
{
|
{
|
||||||
static constexpr unsigned size_per_battery = MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
static constexpr unsigned size_per_battery = MAVLINK_MSG_ID_BATTERY_INFO_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||||
return size_per_battery * _battery_status_subs.advertised_count();
|
return size_per_battery * _battery_status_subs.advertised_count();
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
explicit MavlinkStreamSmartBatteryInfo(Mavlink *mavlink) : MavlinkStream(mavlink) {}
|
explicit MavlinkStreamBatteryInfo(Mavlink *mavlink) : MavlinkStream(mavlink) {}
|
||||||
|
|
||||||
uORB::SubscriptionMultiArray<battery_status_s, battery_status_s::MAX_INSTANCES> _battery_status_subs{ORB_ID::battery_status};
|
uORB::SubscriptionMultiArray<battery_status_s, battery_status_s::MAX_INSTANCES> _battery_status_subs{ORB_ID::battery_status};
|
||||||
|
|
||||||
|
@ -67,36 +67,50 @@ private:
|
||||||
|
|
||||||
if (battery_sub.update(&battery_status)) {
|
if (battery_sub.update(&battery_status)) {
|
||||||
if (battery_status.serial_number == 0) {
|
if (battery_status.serial_number == 0) {
|
||||||
// This is not smart battery
|
// Required to emit
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
mavlink_smart_battery_info_t msg{};
|
mavlink_battery_info_t msg{};
|
||||||
|
|
||||||
msg.id = battery_status.id - 1;
|
msg.id = battery_status.id - 1;
|
||||||
msg.capacity_full_specification = battery_status.capacity;
|
msg.design_capacity = (float)(battery_status.capacity * 1000);
|
||||||
msg.capacity_full = (int32_t)((float)(battery_status.state_of_health * battery_status.capacity) / 100.f);
|
msg.full_charge_capacity = (float)(battery_status.state_of_health * battery_status.capacity * 1000.f) / 100.f;
|
||||||
msg.cycle_count = battery_status.cycle_count;
|
msg.cycle_count = battery_status.cycle_count;
|
||||||
|
|
||||||
if (battery_status.manufacture_date) {
|
if (battery_status.manufacture_date) {
|
||||||
uint16_t day = battery_status.manufacture_date % 32;
|
uint16_t day = battery_status.manufacture_date % 32;
|
||||||
uint16_t month = (battery_status.manufacture_date >> 5) % 16;
|
uint16_t month = (battery_status.manufacture_date >> 5) % 16;
|
||||||
uint16_t year = (80 + (battery_status.manufacture_date >> 9)) % 100;
|
uint16_t year = (80 + (battery_status.manufacture_date >> 9));
|
||||||
|
uint16_t year2dig = year % 100;
|
||||||
|
|
||||||
|
//Formatted as 'ddmmyyyy' (maxed 9 chars)
|
||||||
|
snprintf(msg.manufacture_date, sizeof(msg.manufacture_date), "%d%d%d", day, month, year);
|
||||||
//Formatted as 'dd/mm/yy-123456' (maxed 15 + 1 chars)
|
//Formatted as 'dd/mm/yy-123456' (maxed 15 + 1 chars)
|
||||||
snprintf(msg.serial_number, sizeof(msg.serial_number), "%d/%d/%d-%d", day, month, year, battery_status.serial_number);
|
snprintf(msg.serial_number, sizeof(msg.serial_number), "%d/%d/%d-%d", day, month, year2dig,
|
||||||
|
battery_status.serial_number);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
|
|
||||||
snprintf(msg.serial_number, sizeof(msg.serial_number), "%d", battery_status.serial_number);
|
snprintf(msg.serial_number, sizeof(msg.serial_number), "%d", battery_status.serial_number);
|
||||||
}
|
}
|
||||||
|
|
||||||
//msg.device_name = ??
|
// Not supported by PX4 (not in battery_status uorb topic)
|
||||||
msg.weight = -1;
|
/*
|
||||||
msg.discharge_minimum_voltage = -1;
|
msg.name = 0; // char[50]
|
||||||
msg.charging_minimum_voltage = -1;
|
msg.weight = 0;
|
||||||
msg.resting_minimum_voltage = -1;
|
msg.discharge_minimum_voltage = 0;
|
||||||
|
msg.charging_minimum_voltage = 0;
|
||||||
|
msg.resting_minimum_voltage = 0;
|
||||||
|
msg.charging_maximum_voltage = 0;
|
||||||
|
msg.charging_maximum_current = 0;
|
||||||
|
msg.discharge_maximum_current = 0;
|
||||||
|
msg.discharge_maximum_burst_current = 0;
|
||||||
|
msg.cells_in_series = 0;
|
||||||
|
msg.nominal_voltage = 0;
|
||||||
|
*/
|
||||||
|
|
||||||
mavlink_msg_smart_battery_info_send_struct(_mavlink->get_channel(), &msg);
|
mavlink_msg_battery_info_send_struct(_mavlink->get_channel(), &msg);
|
||||||
updated = true;
|
updated = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -105,4 +119,4 @@ private:
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // SMART_BATTERY_INFO_HPP
|
#endif // BATTERY_INFO_HPP
|
Loading…
Reference in New Issue