AP_BattMonitor.cpp 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516
  1. #include "AP_BattMonitor.h"
  2. #include "AP_BattMonitor_Analog.h"
  3. #include "AP_BattMonitor_SMBus.h"
  4. #include "AP_BattMonitor_Bebop.h"
  5. #include "AP_BattMonitor_BLHeliESC.h"
  6. #include "AP_BattMonitor_Sum.h"
  7. #include "AP_BattMonitor_FuelFlow.h"
  8. #include "AP_BattMonitor_FuelLevel_PWM.h"
  9. #include <AP_HAL/AP_HAL.h>
  10. #if HAL_WITH_UAVCAN
  11. #include "AP_BattMonitor_UAVCAN.h"
  12. #endif
  13. #include <AP_Vehicle/AP_Vehicle_Type.h>
  14. #include <AP_Logger/AP_Logger.h>
  15. #include <GCS_MAVLink/GCS.h>
  16. #include <AP_Notify/AP_Notify.h>
  17. extern const AP_HAL::HAL& hal;
  18. AP_BattMonitor *AP_BattMonitor::_singleton;
  19. const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
  20. // 0 - 18, 20- 22 used by old parameter indexes
  21. // @Group: _
  22. // @Path: AP_BattMonitor_Params.cpp
  23. AP_SUBGROUPINFO(_params[0], "_", 23, AP_BattMonitor, AP_BattMonitor_Params),
  24. // @Group: 2_
  25. // @Path: AP_BattMonitor_Params.cpp
  26. AP_SUBGROUPINFO(_params[1], "2_", 24, AP_BattMonitor, AP_BattMonitor_Params),
  27. // @Group: 3_
  28. // @Path: AP_BattMonitor_Params.cpp
  29. AP_SUBGROUPINFO(_params[2], "3_", 25, AP_BattMonitor, AP_BattMonitor_Params),
  30. // @Group: 4_
  31. // @Path: AP_BattMonitor_Params.cpp
  32. AP_SUBGROUPINFO(_params[3], "4_", 26, AP_BattMonitor, AP_BattMonitor_Params),
  33. // @Group: 5_
  34. // @Path: AP_BattMonitor_Params.cpp
  35. AP_SUBGROUPINFO(_params[4], "5_", 27, AP_BattMonitor, AP_BattMonitor_Params),
  36. // @Group: 6_
  37. // @Path: AP_BattMonitor_Params.cpp
  38. AP_SUBGROUPINFO(_params[5], "6_", 28, AP_BattMonitor, AP_BattMonitor_Params),
  39. // @Group: 7_
  40. // @Path: AP_BattMonitor_Params.cpp
  41. AP_SUBGROUPINFO(_params[6], "7_", 29, AP_BattMonitor, AP_BattMonitor_Params),
  42. // @Group: 8_
  43. // @Path: AP_BattMonitor_Params.cpp
  44. AP_SUBGROUPINFO(_params[7], "8_", 30, AP_BattMonitor, AP_BattMonitor_Params),
  45. // @Group: 9_
  46. // @Path: AP_BattMonitor_Params.cpp
  47. AP_SUBGROUPINFO(_params[8], "9_", 31, AP_BattMonitor, AP_BattMonitor_Params),
  48. AP_GROUPEND
  49. };
  50. // Default constructor.
  51. // Note that the Vector/Matrix constructors already implicitly zero
  52. // their values.
  53. //
  54. AP_BattMonitor::AP_BattMonitor(uint32_t log_battery_bit, battery_failsafe_handler_fn_t battery_failsafe_handler_fn, const int8_t *failsafe_priorities) :
  55. _log_battery_bit(log_battery_bit),
  56. _num_instances(0),
  57. _battery_failsafe_handler_fn(battery_failsafe_handler_fn),
  58. _failsafe_priorities(failsafe_priorities)
  59. {
  60. AP_Param::setup_object_defaults(this, var_info);
  61. if (_singleton != nullptr) {
  62. AP_HAL::panic("AP_BattMonitor must be singleton");
  63. }
  64. _singleton = this;
  65. }
  66. // init - instantiate the battery monitors
  67. void
  68. AP_BattMonitor::init()
  69. {
  70. // check init has not been called before
  71. if (_num_instances != 0) {
  72. return;
  73. }
  74. _highest_failsafe_priority = INT8_MAX;
  75. convert_params();
  76. #ifdef HAL_BATT_MONITOR_DEFAULT
  77. if (_params[0]._type == 0) {
  78. // we can't use set_default() as the type is used as a flag for parameter conversion
  79. _params[0]._type.set((AP_BattMonitor_Params::BattMonitor_Type)HAL_BATT_MONITOR_DEFAULT);
  80. }
  81. #endif
  82. // create each instance
  83. for (uint8_t instance=0; instance<AP_BATT_MONITOR_MAX_INSTANCES; instance++) {
  84. // clear out the cell voltages
  85. memset(&state[instance].cell_voltages, 0xFF, sizeof(cells));
  86. switch (get_type(instance)) {
  87. case AP_BattMonitor_Params::BattMonitor_TYPE_ANALOG_VOLTAGE_ONLY:
  88. case AP_BattMonitor_Params::BattMonitor_TYPE_ANALOG_VOLTAGE_AND_CURRENT:
  89. drivers[instance] = new AP_BattMonitor_Analog(*this, state[instance], _params[instance]);
  90. break;
  91. case AP_BattMonitor_Params::BattMonitor_TYPE_SOLO:
  92. drivers[instance] = new AP_BattMonitor_SMBus_Solo(*this, state[instance], _params[instance],
  93. hal.i2c_mgr->get_device(AP_BATTMONITOR_SMBUS_BUS_INTERNAL, AP_BATTMONITOR_SMBUS_I2C_ADDR,
  94. 100000, true, 20));
  95. break;
  96. case AP_BattMonitor_Params::BattMonitor_TYPE_MAXELL:
  97. drivers[instance] = new AP_BattMonitor_SMBus_Maxell(*this, state[instance], _params[instance],
  98. hal.i2c_mgr->get_device(AP_BATTMONITOR_SMBUS_BUS_EXTERNAL, AP_BATTMONITOR_SMBUS_I2C_ADDR,
  99. 100000, true, 20));
  100. break;
  101. case AP_BattMonitor_Params::BattMonitor_TYPE_BEBOP:
  102. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
  103. drivers[instance] = new AP_BattMonitor_Bebop(*this, state[instance], _params[instance]);
  104. #endif
  105. break;
  106. case AP_BattMonitor_Params::BattMonitor_TYPE_UAVCAN_BatteryInfo:
  107. #if HAL_WITH_UAVCAN
  108. drivers[instance] = new AP_BattMonitor_UAVCAN(*this, state[instance], AP_BattMonitor_UAVCAN::UAVCAN_BATTERY_INFO, _params[instance]);
  109. #endif
  110. break;
  111. case AP_BattMonitor_Params::BattMonitor_TYPE_BLHeliESC:
  112. #ifdef HAVE_AP_BLHELI_SUPPORT
  113. drivers[instance] = new AP_BattMonitor_BLHeliESC(*this, state[instance], _params[instance]);
  114. #endif
  115. break;
  116. case AP_BattMonitor_Params::BattMonitor_TYPE_Sum:
  117. drivers[instance] = new AP_BattMonitor_Sum(*this, state[instance], _params[instance], instance);
  118. break;
  119. case AP_BattMonitor_Params::BattMonitor_TYPE_FuelFlow:
  120. drivers[instance] = new AP_BattMonitor_FuelFlow(*this, state[instance], _params[instance]);
  121. break;
  122. case AP_BattMonitor_Params::BattMonitor_TYPE_FuelLevel_PWM:
  123. drivers[instance] = new AP_BattMonitor_FuelLevel_PWM(*this, state[instance], _params[instance]);
  124. break;
  125. case AP_BattMonitor_Params::BattMonitor_TYPE_NONE:
  126. default:
  127. break;
  128. }
  129. // call init function for each backend
  130. if (drivers[instance] != nullptr) {
  131. drivers[instance]->init();
  132. // _num_instances is actually the index for looping over instances
  133. // the user may have BATT_MONITOR=0 and BATT2_MONITOR=7, in which case
  134. // there will be a gap, but as we always check for drivers[instances] being nullptr
  135. // this is safe
  136. _num_instances = instance + 1;
  137. }
  138. }
  139. }
  140. void AP_BattMonitor::convert_params(void) {
  141. if (_params[0]._type.configured_in_storage()) {
  142. // _params[0]._type will always be configured in storage after conversion is done the first time
  143. return;
  144. }
  145. #define SECOND_BATT_CONVERT_MASK 0x80
  146. const struct ConversionTable {
  147. uint8_t old_element;
  148. uint8_t new_index; // upper bit used to indicate if its the first or second instance
  149. }conversionTable[22] = {
  150. { 0, 0 }, // _MONITOR
  151. { 1, 1 }, // _VOLT_PIN
  152. { 2, 2 }, // _CURR_PIN
  153. { 3, 3 }, // _VOLT_MULT
  154. { 4, 4 }, // _AMP_PERVOLT
  155. { 5, 5 }, // _AMP_OFFSET
  156. { 6, 6 }, // _CAPACITY
  157. { 9, 7 }, // _WATT_MAX
  158. {10, 8 }, // _SERIAL_NUM
  159. {11, (SECOND_BATT_CONVERT_MASK | 0)}, // 2_MONITOR
  160. {12, (SECOND_BATT_CONVERT_MASK | 1)}, // 2_VOLT_PIN
  161. {13, (SECOND_BATT_CONVERT_MASK | 2)}, // 2_CURR_PIN
  162. {14, (SECOND_BATT_CONVERT_MASK | 3)}, // 2_VOLT_MULT
  163. {15, (SECOND_BATT_CONVERT_MASK | 4)}, // 2_AMP_PERVOLT
  164. {16, (SECOND_BATT_CONVERT_MASK | 5)}, // 2_AMP_OFFSET
  165. {17, (SECOND_BATT_CONVERT_MASK | 6)}, // 2_CAPACITY
  166. {18, (SECOND_BATT_CONVERT_MASK | 7)}, // 2_WATT_MAX
  167. {20, (SECOND_BATT_CONVERT_MASK | 8)}, // 2_SERIAL_NUM
  168. {21, 9 }, // _LOW_TIMER
  169. {22, 10 }, // _LOW_TYPE
  170. {21, (SECOND_BATT_CONVERT_MASK | 9)}, // 2_LOW_TIMER
  171. {22, (SECOND_BATT_CONVERT_MASK |10)}, // 2_LOW_TYPE
  172. };
  173. char param_name[17];
  174. AP_Param::ConversionInfo info;
  175. info.new_name = param_name;
  176. #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
  177. info.old_key = 166;
  178. #elif APM_BUILD_TYPE(APM_BUILD_ArduCopter)
  179. info.old_key = 36;
  180. #elif APM_BUILD_TYPE(APM_BUILD_ArduSub)
  181. info.old_key = 33;
  182. #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
  183. info.old_key = 145;
  184. #else
  185. _params[0]._type.save(true);
  186. return; // no conversion is supported on this platform
  187. #endif
  188. for (uint8_t i = 0; i < ARRAY_SIZE(conversionTable); i++) {
  189. uint8_t param_instance = conversionTable[i].new_index >> 7;
  190. uint8_t destination_index = 0x7F & conversionTable[i].new_index;
  191. info.old_group_element = conversionTable[i].old_element;
  192. info.type = (ap_var_type)AP_BattMonitor_Params::var_info[destination_index].type;
  193. if (param_instance) {
  194. hal.util->snprintf(param_name, sizeof(param_name), "BATT2_%s", AP_BattMonitor_Params::var_info[destination_index].name);
  195. } else {
  196. hal.util->snprintf(param_name, sizeof(param_name), "BATT_%s", AP_BattMonitor_Params::var_info[destination_index].name);
  197. }
  198. AP_Param::convert_old_parameter(&info, 1.0f, 0);
  199. }
  200. // force _params[0]._type into storage to flag that conversion has been done
  201. _params[0]._type.save(true);
  202. }
  203. // read - read the voltage and current for all instances
  204. void
  205. AP_BattMonitor::read()
  206. {
  207. for (uint8_t i=0; i<_num_instances; i++) {
  208. if (drivers[i] != nullptr && _params[i].type() != AP_BattMonitor_Params::BattMonitor_TYPE_NONE) {
  209. drivers[i]->read();
  210. drivers[i]->update_resistance_estimate();
  211. }
  212. }
  213. AP_Logger *logger = AP_Logger::get_singleton();
  214. if (logger->should_log(_log_battery_bit)) {
  215. logger->Write_Current();
  216. logger->Write_Power();
  217. }
  218. check_failsafes();
  219. checkPoweringOff();
  220. }
  221. // healthy - returns true if monitor is functioning
  222. bool AP_BattMonitor::healthy(uint8_t instance) const {
  223. return instance < _num_instances && state[instance].healthy;
  224. }
  225. /// voltage - returns battery voltage in volts
  226. float AP_BattMonitor::voltage(uint8_t instance) const
  227. {
  228. if (instance < _num_instances) {
  229. return state[instance].voltage;
  230. } else {
  231. return 0.0f;
  232. }
  233. }
  234. /// get voltage with sag removed (based on battery current draw and resistance)
  235. /// this will always be greater than or equal to the raw voltage
  236. float AP_BattMonitor::voltage_resting_estimate(uint8_t instance) const
  237. {
  238. if (instance < _num_instances && drivers[instance] != nullptr) {
  239. return drivers[instance]->voltage_resting_estimate();
  240. } else {
  241. return 0.0f;
  242. }
  243. }
  244. /// current_amps - returns the instantaneous current draw in amperes
  245. bool AP_BattMonitor::current_amps(float &current, uint8_t instance) const {
  246. if ((instance < _num_instances) && (drivers[instance] != nullptr) && drivers[instance]->has_current()) {
  247. current = state[instance].current_amps;
  248. return true;
  249. } else {
  250. return false;
  251. }
  252. }
  253. /// consumed_mah - returns total current drawn since start-up in milliampere.hours
  254. bool AP_BattMonitor::consumed_mah(float &mah, const uint8_t instance) const {
  255. if ((instance < _num_instances) && (drivers[instance] != nullptr) && drivers[instance]->has_current()) {
  256. mah = state[instance].consumed_mah;
  257. return true;
  258. } else {
  259. return false;
  260. }
  261. }
  262. /// consumed_wh - returns energy consumed since start-up in Watt.hours
  263. bool AP_BattMonitor::consumed_wh(float &wh, const uint8_t instance) const {
  264. if (instance < _num_instances && drivers[instance] != nullptr && drivers[instance]->has_consumed_energy()) {
  265. wh = state[instance].consumed_wh;
  266. return true;
  267. } else {
  268. return false;
  269. }
  270. }
  271. /// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
  272. uint8_t AP_BattMonitor::capacity_remaining_pct(uint8_t instance) const
  273. {
  274. if (instance < _num_instances && drivers[instance] != nullptr) {
  275. return drivers[instance]->capacity_remaining_pct();
  276. } else {
  277. return 0;
  278. }
  279. }
  280. /// pack_capacity_mah - returns the capacity of the battery pack in mAh when the pack is full
  281. int32_t AP_BattMonitor::pack_capacity_mah(uint8_t instance) const
  282. {
  283. if (instance < AP_BATT_MONITOR_MAX_INSTANCES) {
  284. return _params[instance]._pack_capacity;
  285. } else {
  286. return 0;
  287. }
  288. }
  289. void AP_BattMonitor::check_failsafes(void)
  290. {
  291. if (hal.util->get_soft_armed()) {
  292. for (uint8_t i = 0; i < _num_instances; i++) {
  293. if (drivers[i] == nullptr) {
  294. continue;
  295. }
  296. const BatteryFailsafe type = drivers[i]->update_failsafes();
  297. if (type <= state[i].failsafe) {
  298. continue;
  299. }
  300. int8_t action = 0;
  301. const char *type_str = nullptr;
  302. switch (type) {
  303. case AP_BattMonitor::BatteryFailsafe_None:
  304. continue; // should not have been called in this case
  305. case AP_BattMonitor::BatteryFailsafe_Low:
  306. action = _params[i]._failsafe_low_action;
  307. type_str = "low";
  308. break;
  309. case AP_BattMonitor::BatteryFailsafe_Critical:
  310. action = _params[i]._failsafe_critical_action;
  311. type_str = "critical";
  312. break;
  313. }
  314. gcs().send_text(MAV_SEVERITY_WARNING, "Battery %d is %s %.2fV used %.0f mAh", i + 1, type_str,
  315. (double)voltage(i), (double)state[i].consumed_mah);
  316. _has_triggered_failsafe = true;
  317. AP_Notify::flags.failsafe_battery = true;
  318. state[i].failsafe = type;
  319. // map the desired failsafe action to a prioritiy level
  320. int8_t priority = 0;
  321. if (_failsafe_priorities != nullptr) {
  322. while (_failsafe_priorities[priority] != -1) {
  323. if (_failsafe_priorities[priority] == action) {
  324. break;
  325. }
  326. priority++;
  327. }
  328. }
  329. // trigger failsafe if the action was equal or higher priority
  330. // It's valid to retrigger the same action if a different battery provoked the event
  331. if (priority <= _highest_failsafe_priority) {
  332. _battery_failsafe_handler_fn(type_str, action);
  333. _highest_failsafe_priority = priority;
  334. }
  335. }
  336. }
  337. }
  338. // return true if any battery is pushing too much power
  339. bool AP_BattMonitor::overpower_detected() const
  340. {
  341. bool result = false;
  342. for (uint8_t instance = 0; instance < _num_instances; instance++) {
  343. result |= overpower_detected(instance);
  344. }
  345. return result;
  346. }
  347. bool AP_BattMonitor::overpower_detected(uint8_t instance) const
  348. {
  349. #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
  350. if (instance < _num_instances && _params[instance]._watt_max > 0) {
  351. float power = state[instance].current_amps * state[instance].voltage;
  352. return state[instance].healthy && (power > _params[instance]._watt_max);
  353. }
  354. return false;
  355. #else
  356. return false;
  357. #endif
  358. }
  359. bool AP_BattMonitor::has_cell_voltages(const uint8_t instance) const
  360. {
  361. if (instance < _num_instances && drivers[instance] != nullptr) {
  362. return drivers[instance]->has_cell_voltages();
  363. }
  364. return false;
  365. }
  366. // return the current cell voltages, returns the first monitor instances cells if the instance is out of range
  367. const AP_BattMonitor::cells & AP_BattMonitor::get_cell_voltages(const uint8_t instance) const
  368. {
  369. if (instance >= AP_BATT_MONITOR_MAX_INSTANCES) {
  370. return state[AP_BATT_PRIMARY_INSTANCE].cell_voltages;
  371. } else {
  372. return state[instance].cell_voltages;
  373. }
  374. }
  375. // returns true if there is a temperature reading
  376. bool AP_BattMonitor::get_temperature(float &temperature, const uint8_t instance) const
  377. {
  378. if (instance >= AP_BATT_MONITOR_MAX_INSTANCES) {
  379. return false;
  380. } else {
  381. temperature = state[instance].temperature;
  382. return (AP_HAL::millis() - state[instance].temperature_time) <= AP_BATT_MONITOR_TIMEOUT;
  383. }
  384. }
  385. bool AP_BattMonitor::arming_checks(size_t buflen, char *buffer) const
  386. {
  387. char temp_buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
  388. for (uint8_t i = 0; i < AP_BATT_MONITOR_MAX_INSTANCES; i++) {
  389. if (drivers[i] != nullptr && !(drivers[i]->arming_checks(temp_buffer, sizeof(temp_buffer)))) {
  390. hal.util->snprintf(buffer, buflen, "Battery %d %s", i + 1, temp_buffer);
  391. return false;
  392. }
  393. }
  394. return true;
  395. }
  396. // Check's each smart battery instance for its powering off state and broadcasts notifications
  397. void AP_BattMonitor::checkPoweringOff(void)
  398. {
  399. for (uint8_t i = 0; i < _num_instances; i++) {
  400. if (state[i].is_powering_off && !state[i].powerOffNotified) {
  401. // Set the AP_Notify flag, which plays the power off tones
  402. AP_Notify::flags.powering_off = true;
  403. // Send a Mavlink broadcast announcing the shutdown
  404. mavlink_message_t msg;
  405. mavlink_command_long_t cmd_msg{};
  406. cmd_msg.command = MAV_CMD_POWER_OFF_INITIATED;
  407. cmd_msg.param1 = i+1;
  408. mavlink_msg_command_long_encode(mavlink_system.sysid, MAV_COMP_ID_ALL, &msg, &cmd_msg);
  409. GCS_MAVLINK::send_to_components(msg);
  410. gcs().send_text(MAV_SEVERITY_WARNING, "Vehicle %d battery %d is powering off", mavlink_system.sysid, i+1);
  411. // only send this once
  412. state[i].powerOffNotified = true;
  413. }
  414. }
  415. }
  416. /*
  417. reset battery remaining percentage for batteries that integrate to
  418. calculate percentage remaining
  419. */
  420. bool AP_BattMonitor::reset_remaining(uint16_t battery_mask, float percentage)
  421. {
  422. bool ret = true;
  423. BatteryFailsafe highest_failsafe = BatteryFailsafe_None;
  424. for (uint8_t i = 0; i < _num_instances; i++) {
  425. if ((1U<<i) & battery_mask) {
  426. ret &= drivers[i]->reset_remaining(percentage);
  427. }
  428. if (state[i].failsafe > highest_failsafe) {
  429. highest_failsafe = state[i].failsafe;
  430. }
  431. }
  432. // If all backends are not in failsafe then set overall failsafe state
  433. if (highest_failsafe == BatteryFailsafe_None) {
  434. _highest_failsafe_priority = INT8_MAX;
  435. _has_triggered_failsafe = false;
  436. // and reset notify flag
  437. AP_Notify::flags.failsafe_battery = false;
  438. }
  439. return ret;
  440. }
  441. namespace AP {
  442. AP_BattMonitor &battery()
  443. {
  444. return *AP_BattMonitor::get_singleton();
  445. }
  446. };