@@ -44,6 +44,7 @@ UavcanBatteryBridge::UavcanBatteryBridge(uavcan::INode &node) :
4444 ModuleParams(nullptr ),
4545 _sub_battery(node),
4646 _sub_battery_aux(node),
47+ _sub_cbat(node),
4748 _warning(battery_status_s::WARNING_NONE),
4849 _last_timestamp(0 )
4950{
@@ -78,6 +79,13 @@ int UavcanBatteryBridge::init()
7879 return res;
7980 }
8081
82+ res = _sub_cbat.start (CBATCbBinder (this , &UavcanBatteryBridge::cbat_sub_cb));
83+
84+ if (res < 0 ) {
85+ PX4_ERR (" failed to start uavcan sub: %d" , res);
86+ return res;
87+ }
88+
8189 return 0 ;
8290}
8391
@@ -92,7 +100,8 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure<uavcan::
92100 }
93101 }
94102
95- if (instance >= battery_status_s::MAX_INSTANCES) {
103+ if (instance >= battery_status_s::MAX_INSTANCES
104+ || _batt_update_mod[instance] == BatteryDataType::CBAT) {
96105 return ;
97106 }
98107
@@ -165,11 +174,9 @@ UavcanBatteryBridge::battery_aux_sub_cb(const uavcan::ReceivedDataStructure<ardu
165174 }
166175 }
167176
168- if (instance >= battery_status_s::MAX_INSTANCES) {
169- return ;
170- }
171-
172- if (_batt_update_mod[instance] == BatteryDataType::Filter) {
177+ if (instance >= battery_status_s::MAX_INSTANCES
178+ || _batt_update_mod[instance] == BatteryDataType::Filter
179+ || _batt_update_mod[instance] == BatteryDataType::CBAT) {
173180 return ;
174181 }
175182
@@ -197,6 +204,92 @@ UavcanBatteryBridge::battery_aux_sub_cb(const uavcan::ReceivedDataStructure<ardu
197204 }
198205}
199206
207+ void UavcanBatteryBridge::cbat_sub_cb (const uavcan::ReceivedDataStructure<cuav::equipment::power::CBAT> &msg)
208+ {
209+ uint8_t instance = 0 ;
210+
211+ for (instance = 0 ; instance < battery_status_s::MAX_INSTANCES; instance++) {
212+ if (_battery_status[instance].id == msg.getSrcNodeID ().get ()) {
213+ break ;
214+ }
215+ }
216+
217+ if (instance >= battery_status_s::MAX_INSTANCES
218+ || _batt_update_mod[instance] == BatteryDataType::Filter) {
219+ return ;
220+ }
221+
222+ // If CBAT message with superset of data was received, skip BatteryInfo messages
223+ _batt_update_mod[instance] = BatteryDataType::CBAT;
224+
225+ _battery_status[instance].timestamp = hrt_absolute_time ();
226+ _battery_status[instance].voltage_v = msg.voltage ;
227+ _battery_status[instance].current_a = -msg.current ; // discharge reported negative
228+ _battery_status[instance].current_average_a = -msg.average_current ; // discharge reported negative
229+ _battery_status[instance].discharged_mah = msg.full_charge_capacity - msg.remaining_capacity ; // mAh
230+ _battery_status[instance].remaining = msg.state_of_charge / 100 .f ;
231+ _battery_status[instance].scale = -1 .f ; // not supported, needs to be computed centrally
232+ _battery_status[instance].temperature = msg.temperature + atmosphere::kAbsoluteNullCelsius ; // Kelvin to Celsius
233+ _battery_status[instance].full_charge_capacity_wh =
234+ msg.full_charge_capacity * msg.nominal_voltage / 1000 .f ; // mAh -> Wh
235+ _battery_status[instance].remaining_capacity_wh = msg.remaining_capacity * msg.nominal_voltage / 1000 .f ; // mAh -> Wh
236+ _battery_status[instance].nominal_voltage = msg.nominal_voltage ;
237+ _battery_status[instance].capacity = msg.design_capacity ; // mAh
238+ _battery_status[instance].cycle_count = msg.cycle_count ;
239+ _battery_status[instance].average_time_to_empty = msg.average_time_to_empty ;
240+ _battery_status[instance].manufacture_date = msg.manufacture_date ;
241+ _battery_status[instance].state_of_health = msg.state_of_health ;
242+ _battery_status[instance].max_error = msg.max_error ;
243+ _battery_status[instance].over_discharge_count = msg.over_discharge_count ;
244+ _battery_status[instance].connected = true ;
245+ _battery_status[instance].cell_count = msg.cell_count ;
246+ _battery_status[instance].source = battery_status_s::SOURCE_EXTERNAL;
247+ _battery_status[instance].id = msg.getSrcNodeID ().get ();
248+ _battery_status[instance].is_powering_off = msg.is_powering_off ;
249+
250+ // For time remaining calculation use the average current if supplied
251+ const float remaining_ah = msg.remaining_capacity / 1000 .f ; // mAh -> Ah
252+ const float current_a = math::isZero (_battery_status[instance].current_average_a ) ?
253+ _battery_status[instance].current_a : _battery_status[instance].current_average_a ;
254+ _battery_status[instance].time_remaining_s =
255+ math::isZero (current_a) ? NAN : (remaining_ah / current_a * 3600 .f ); // Ah / A = h * 3600 = s
256+
257+ for (uint8_t i = 0 ; i < _battery_status[instance].cell_count ; i++) {
258+ _battery_status[instance].voltage_cell_v [i] = msg.voltage_cell [i];
259+ }
260+
261+ determineWarning (_battery_status[instance].remaining );
262+ _battery_status[instance].warning = _warning;
263+
264+ uint16_t faults = 0 ;
265+
266+ if (msg.status_flags & cuav::equipment::power::CBAT::STATUS_FLAG_OVERLOAD) {
267+ faults |= (1 << battery_status_s::FAULT_OVER_CURRENT);
268+ }
269+
270+ if (msg.status_flags & cuav::equipment::power::CBAT::STATUS_FLAG_BAD_BATTERY) {
271+ faults |= (1 << battery_status_s::FAULT_HARDWARE_FAILURE);
272+ }
273+
274+ if (msg.status_flags & cuav::equipment::power::CBAT::STATUS_FLAG_TEMP_HOT) {
275+ faults |= (1 << battery_status_s::FAULT_OVER_TEMPERATURE);
276+ }
277+
278+ if (msg.status_flags & cuav::equipment::power::CBAT::STATUS_FLAG_TEMP_COLD) {
279+ faults |= (1 << battery_status_s::FAULT_UNDER_TEMPERATURE);
280+ }
281+
282+ _battery_status[instance].faults = faults;
283+
284+ publish (msg.getSrcNodeID ().get (), &_battery_status[instance]);
285+
286+ _battery_info[instance].timestamp = _battery_status[instance].timestamp ;
287+ _battery_info[instance].id = _battery_status[instance].id ;
288+ snprintf (_battery_info[instance].serial_number , sizeof (_battery_info[instance].serial_number ), " %" PRIu16,
289+ msg.serial_number );
290+ _battery_info_pub[instance].publish (_battery_info[instance]);
291+ }
292+
200293void
201294UavcanBatteryBridge::sumDischarged (hrt_abstime timestamp, float current_a)
202295{
0 commit comments