15 #define debug_bm_uavcan(level, fmt, args...) do { if ((level) <= AP_BoardConfig_CAN::get_can_debug()) { printf(fmt, ##args); }} while (0) 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) {
32 if (uavcan !=
nullptr) {
34 case UAVCAN_BATTERY_INFO:
69 float mah = (float) ((
double)
_state.
current_amps * (double) dt * (
double) 0.0000002778f);
AP_BattMonitor_UAVCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_UAVCAN_Type type, AP_BattMonitor_Params ¶ms)
Constructor.
AP_BattMonitor_Params & _params
#define AP_BATTMONITOR_UAVCAN_TIMEOUT_MICROS
AP_HAL::CANManager ** can_mgr
uint32_t last_time_micros
Common definitions and utility routines for the ArduPilot libraries.
AP_BattMonitor::BattMonitor_State & _state
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)
void handle_bi_msg(float voltage, float current, float temperature) override