Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/AP_Periph/battery.cpp
Views: 1798
#include "AP_Periph.h"12#ifdef HAL_PERIPH_ENABLE_BATTERY34/*5battery support6*/78#include <dronecan_msgs.h>910extern const AP_HAL::HAL &hal;1112#ifndef AP_PERIPH_BATTERY_MODEL_NAME13#define AP_PERIPH_BATTERY_MODEL_NAME CAN_APP_NODE_NAME14#endif1516/*17update CAN battery monitor18*/19void AP_Periph_FW::can_battery_update(void)20{21const uint32_t now_ms = AP_HAL::millis();22if (now_ms - battery.last_can_send_ms < 100) {23return;24}25battery.last_can_send_ms = now_ms;2627const uint8_t battery_instances = battery_lib.num_instances();28for (uint8_t i=0; i<battery_instances; i++) {29if (BIT_IS_SET(g.battery_hide_mask, i)) {30// do not transmit this battery31continue;32}33if (!battery_lib.healthy(i)) {34continue;35}3637uavcan_equipment_power_BatteryInfo pkt {};3839// if a battery serial number is assigned, use that as the ID. Else, use the index.40const int32_t serial_number = battery_lib.get_serial_number(i);41pkt.battery_id = (serial_number >= 0) ? serial_number : i+1;4243pkt.voltage = battery_lib.voltage(i);4445float current;46if (battery_lib.current_amps(current, i)) {47pkt.current = current;48}49float temperature;50if (battery_lib.get_temperature(temperature, i)) {51// Battery lib reports temperature in Celsius.52// Convert Celsius to Kelvin for transmission on CAN.53pkt.temperature = C_TO_KELVIN(temperature);54}5556pkt.state_of_health_pct = UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN;57uint8_t percentage = 0;58if (battery_lib.capacity_remaining_pct(percentage, i)) {59pkt.state_of_charge_pct = percentage;60}61pkt.model_instance_id = i+1;6263#if !defined(HAL_PERIPH_BATTERY_SKIP_NAME)64// example model_name: "org.ardupilot.ap_periph SN 123"65hal.util->snprintf((char*)pkt.model_name.data, sizeof(pkt.model_name.data), "%s %ld", AP_PERIPH_BATTERY_MODEL_NAME, (long int)serial_number);66pkt.model_name.len = strnlen((char*)pkt.model_name.data, sizeof(pkt.model_name.data));67#endif //defined(HAL_PERIPH_BATTERY_SKIP_NAME)6869uint8_t buffer[UAVCAN_EQUIPMENT_POWER_BATTERYINFO_MAX_SIZE];70const uint16_t total_size = uavcan_equipment_power_BatteryInfo_encode(&pkt, buffer, !periph.canfdout());7172canard_broadcast(UAVCAN_EQUIPMENT_POWER_BATTERYINFO_SIGNATURE,73UAVCAN_EQUIPMENT_POWER_BATTERYINFO_ID,74CANARD_TRANSFER_PRIORITY_LOW,75&buffer[0],76total_size);7778// Send individual cell information if available79if (battery_lib.has_cell_voltages(i)) {80can_battery_send_cells(i);81}82}83}8485/*86send individual cell voltages if available87*/88void AP_Periph_FW::can_battery_send_cells(uint8_t instance)89{90// allocate space for the packet. This is a large91// packet that won't fit on the stack, so dynamically allocate92auto* pkt = NEW_NOTHROW ardupilot_equipment_power_BatteryInfoAux;93uint8_t* buffer = NEW_NOTHROW uint8_t[ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_MAX_SIZE];94if (pkt == nullptr || buffer == nullptr) {95delete pkt;96delete [] buffer;97return;98}99const auto &cell_voltages = battery_lib.get_cell_voltages(instance);100101for (uint8_t i = 0; i < ARRAY_SIZE(cell_voltages.cells); i++) {102if (cell_voltages.cells[i] == 0xFFFFU) {103break;104}105pkt->voltage_cell.data[i] = cell_voltages.cells[i]*0.001;106pkt->voltage_cell.len = i+1;107}108109pkt->max_current = nanf("");110pkt->nominal_voltage = nanf("");111112// encode and send message:113const uint16_t total_size = ardupilot_equipment_power_BatteryInfoAux_encode(pkt, buffer, !periph.canfdout());114115canard_broadcast(ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_SIGNATURE,116ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_ID,117CANARD_TRANSFER_PRIORITY_LOW,118buffer,119total_size);120121// Delete temporary buffers122delete pkt;123delete [] buffer;124}125126#endif // HAL_PERIPH_ENABLE_BATTERY127128129130