mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 06:36:45 +08:00
uavcan battery: switch to battery_info.serial_number
This commit is contained in:
committed by
Silvan Fuhrer
parent
3ec684153a
commit
a18453d632
@@ -125,7 +125,6 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure<uavcan::
|
||||
// _battery_status[instance].cycle_count = msg.;
|
||||
_battery_status[instance].time_remaining_s = NAN;
|
||||
// _battery_status[instance].average_time_to_empty = msg.;
|
||||
_battery_status[instance].serial_number = msg.model_instance_id;
|
||||
_battery_status[instance].id = msg.getSrcNodeID().get();
|
||||
|
||||
if (_batt_update_mod[instance] == BatteryDataType::Raw) {
|
||||
@@ -143,8 +142,14 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure<uavcan::
|
||||
determineWarning(_battery_status[instance].remaining);
|
||||
_battery_status[instance].warning = _warning;
|
||||
|
||||
_battery_info[instance].timestamp = _battery_status[instance].timestamp;
|
||||
_battery_info[instance].id = _battery_status[instance].id;
|
||||
snprintf(_battery_info[instance].serial_number, sizeof(_battery_info[instance].serial_number), "%" PRIu32,
|
||||
msg.model_instance_id);
|
||||
|
||||
if (_batt_update_mod[instance] == BatteryDataType::Raw) {
|
||||
publish(msg.getSrcNodeID().get(), &_battery_status[instance]);
|
||||
_battery_info_pub[instance].publish(_battery_info[instance]);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -238,8 +243,13 @@ UavcanBatteryBridge::filterData(const uavcan::ReceivedDataStructure<uavcan::equi
|
||||
/* Override data that is expected to arrive from UAVCAN msg*/
|
||||
_battery_status[instance] = _battery[instance]->getBatteryStatus();
|
||||
_battery_status[instance].temperature = msg.temperature + atmosphere::kAbsoluteNullCelsius; // Kelvin to Celsius
|
||||
_battery_status[instance].serial_number = msg.model_instance_id;
|
||||
_battery_status[instance].id = msg.getSrcNodeID().get(); // overwrite zeroed index from _battery
|
||||
|
||||
publish(msg.getSrcNodeID().get(), &_battery_status[instance]);
|
||||
|
||||
_battery_info[instance].timestamp = _battery_status[instance].timestamp;
|
||||
_battery_info[instance].id = _battery_status[instance].id;
|
||||
snprintf(_battery_info[instance].serial_number, sizeof(_battery_info[instance].serial_number), "%" PRIu32,
|
||||
msg.model_instance_id);
|
||||
_battery_info_pub[instance].publish(_battery_info[instance]);
|
||||
}
|
||||
|
||||
@@ -38,6 +38,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "sensor_bridge.hpp"
|
||||
#include <uORB/topics/battery_info.h>
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <uavcan/equipment/power/BatteryInfo.hpp>
|
||||
#include <ardupilot/equipment/power/BatteryInfoAux.hpp>
|
||||
@@ -95,6 +96,11 @@ private:
|
||||
float _discharged_mah_loop = 0.f;
|
||||
uint8_t _warning;
|
||||
hrt_abstime _last_timestamp;
|
||||
|
||||
// Separate battery info publication because UavcanSensorBridgeBase only supports publishing one topic
|
||||
uORB::PublicationMulti<battery_info_s> _battery_info_pub[battery_status_s::MAX_INSTANCES] {ORB_ID(battery_info), ORB_ID(battery_info), ORB_ID(battery_info), ORB_ID(battery_info)};
|
||||
|
||||
battery_info_s _battery_info[battery_status_s::MAX_INSTANCES] {};
|
||||
battery_status_s _battery_status[battery_status_s::MAX_INSTANCES] {};
|
||||
BatteryDataType _batt_update_mod[battery_status_s::MAX_INSTANCES] {};
|
||||
|
||||
|
||||
Reference in New Issue
Block a user