diff --git a/src/drivers/uavcan/sensors/battery.cpp b/src/drivers/uavcan/sensors/battery.cpp index d41153954a..34323bb5bd 100644 --- a/src/drivers/uavcan/sensors/battery.cpp +++ b/src/drivers/uavcan/sensors/battery.cpp @@ -50,6 +50,19 @@ UavcanBatteryBridge::UavcanBatteryBridge(uavcan::INode &node) : int UavcanBatteryBridge::init() { + int32_t uavcan_sub_bat = 1; + param_get(param_find("UAVCAN_SUB_BAT"), &uavcan_sub_bat); + + for (uint8_t instance = 0; instance < battery_status_s::MAX_INSTANCES; instance++) { + + if (uavcan_sub_bat == FILTER_DATA) { + _batt_update_mod[instance] = BatteryDataType::Filter; + + } else { + _batt_update_mod[instance] = BatteryDataType::Raw; + } + } + int res = _sub_battery.start(BatteryInfoCbBinder(this, &UavcanBatteryBridge::battery_sub_cb)); if (res < 0) { @@ -82,6 +95,12 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure &msg, + uint8_t instance) +{ + _battery.setConnected(true); + _battery.updateVoltage(msg.voltage); + _battery.updateCurrent(msg.current); + _battery.updateBatteryStatus(hrt_absolute_time()); + + /* Override data that is expected to arrive from UAVCAN msg*/ + _battery_status[instance] = _battery.getBatteryStatus(); + _battery_status[instance].temperature = msg.temperature + CONSTANTS_ABSOLUTE_NULL_CELSIUS; // Kelvin to Celcius + _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]); +} diff --git a/src/drivers/uavcan/sensors/battery.hpp b/src/drivers/uavcan/sensors/battery.hpp index 38c2dc7a22..9048da9143 100644 --- a/src/drivers/uavcan/sensors/battery.hpp +++ b/src/drivers/uavcan/sensors/battery.hpp @@ -41,9 +41,12 @@ #include #include #include +#include #include #include +using namespace time_literals; + class UavcanBatteryBridge : public UavcanSensorBridgeBase, public ModuleParams { public: @@ -57,10 +60,18 @@ public: private: + /* Different options to update the battery status */ + enum class BatteryDataType { + Raw, // data from BatteryInfo message only + RawAux, // data combination from BatteryInfo and BatteryInfoAux messages + Filter, // filter data from BatteryInfo message with Battery library + }; + void battery_sub_cb(const uavcan::ReceivedDataStructure &msg); void battery_aux_sub_cb(const uavcan::ReceivedDataStructure &msg); void sumDischarged(hrt_abstime timestamp, float current_a); void determineWarning(float remaining); + void filterData(const uavcan::ReceivedDataStructure &msg, uint8_t instance); typedef uavcan::MethodBinder < UavcanBatteryBridge *, void (UavcanBatteryBridge::*) @@ -85,5 +96,11 @@ private: uint8_t _warning; hrt_abstime _last_timestamp; battery_status_s _battery_status[battery_status_s::MAX_INSTANCES] {}; - bool battery_aux_support[battery_status_s::MAX_INSTANCES] {false}; + BatteryDataType _batt_update_mod[battery_status_s::MAX_INSTANCES] {}; + + static constexpr int FILTER_DATA = 2; + static constexpr int BATTERY_INDEX = 1; + static constexpr int SAMPLE_INTERVAL_US = 20_ms; // assume higher frequency UAVCAN feedback than 50Hz + Battery _battery{BATTERY_INDEX, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_EXTERNAL}; + }; diff --git a/src/drivers/uavcan/uavcan_params.c b/src/drivers/uavcan/uavcan_params.c index 61d6df4816..e43e4ac6e9 100644 --- a/src/drivers/uavcan/uavcan_params.c +++ b/src/drivers/uavcan/uavcan_params.c @@ -228,7 +228,15 @@ PARAM_DEFINE_INT32(UAVCAN_SUB_BARO, 0); * uavcan::equipment::power::BatteryInfo * ardupilot::equipment::power::BatteryInfoAux * - * @boolean + * 0 - Disable + * 1 - Use raw data. Recommended for Smart battery + * 2 - Filter the data with internal battery library + * + * @min 0 + * @max 2 + * @value 0 Disable + * @value 1 Raw data + * @value 2 Filter data * @reboot_required true * @group UAVCAN */