APM:Libraries
AP_BattMonitor_UAVCAN.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if HAL_WITH_UAVCAN
4 
5 #include <AP_Common/AP_Common.h>
6 #include <AP_Math/AP_Math.h>
7 #include "AP_BattMonitor.h"
9 
12 
13 extern const AP_HAL::HAL& hal;
14 
15 #define debug_bm_uavcan(level, fmt, args...) do { if ((level) <= AP_BoardConfig_CAN::get_can_debug()) { printf(fmt, ##args); }} while (0)
16 
19  AP_BattMonitor_Backend(mon, mon_state, params),
20  _type(type)
21 {
22  // starts with not healthy
23  _state.healthy = false;
24 }
25 
27 {
28  if (AP_BoardConfig_CAN::get_can_num_ifaces() != 0) {
29  for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
30  if (hal.can_mgr[i] != nullptr) {
31  AP_UAVCAN *uavcan = hal.can_mgr[i]->get_UAVCAN();
32  if (uavcan != nullptr) {
33  switch (_type) {
34  case UAVCAN_BATTERY_INFO:
36  debug_bm_uavcan(2, "UAVCAN BattMonitor BatteryInfo registered id: %d\n\r", _params._serial_number);
37  }
38  break;
39  }
40  }
41  }
42  }
43  }
44 }
45 
46 // read - read the voltage and current
48 {
49  uint32_t tnow = AP_HAL::micros();
50 
51  // timeout after 5 seconds
53  _state.healthy = false;
54  }
55 }
56 
57 void AP_BattMonitor_UAVCAN::handle_bi_msg(float voltage, float current, float temperature)
58 {
61  _state.current_amps = current;
62 
63  uint32_t tnow = AP_HAL::micros();
64  uint32_t dt = tnow - _state.last_time_micros;
65 
66  // update total current drawn since startup
67  if (_state.last_time_micros != 0 && dt < 2000000) {
68  // .0002778 is 1/3600 (conversion to hours)
69  float mah = (float) ((double) _state.current_amps * (double) dt * (double) 0.0000002778f);
70  _state.consumed_mah += mah;
71  _state.consumed_wh += 0.001f * mah * _state.voltage;
72  }
73 
74  // record time
75  _state.last_time_micros = tnow;
76 
77  _state.healthy = true;
78 }
79 
80 #endif
AP_BattMonitor_UAVCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_UAVCAN_Type type, AP_BattMonitor_Params &params)
Constructor.
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
AP_BattMonitor_Params & _params
#define AP_BATTMONITOR_UAVCAN_TIMEOUT_MICROS
AP_HAL::CANManager ** can_mgr
Definition: HAL.h:120
float temperature
Definition: Airspeed.cpp:32
Common definitions and utility routines for the ArduPilot libraries.
void init() override
AP_BattMonitor::BattMonitor_State & _state
float voltage
void read() override
Read the battery voltage and current. Should be called at 10hz.
AP_Int32 _serial_number
max battery power allowed. Reduce max throttle to reduce current to satisfy t his limit ...
uint8_t register_BM_bi_listener_to_id(AP_BattMonitor_Backend *new_listener, uint8_t id)
uint32_t micros()
Definition: system.cpp:152
void handle_bi_msg(float voltage, float current, float temperature) override