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/batt_balance.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "AP_Periph.h"1617#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE1819#include <dronecan_msgs.h>2021extern const AP_HAL::HAL &hal;2223#ifndef AP_PERIPH_BATTERY_BALANCE_NUMCELLS_DEFAULT24#define AP_PERIPH_BATTERY_BALANCE_NUMCELLS_DEFAULT 025#endif2627#ifndef AP_PERIPH_BATTERY_BALANCE_RATE_DEFAULT28#define AP_PERIPH_BATTERY_BALANCE_RATE_DEFAULT 129#endif3031#ifndef AP_PERIPH_BATTERY_BALANCE_CELL1_PIN_DEFAULT32#define AP_PERIPH_BATTERY_BALANCE_CELL1_PIN_DEFAULT 133#endif3435#ifndef AP_PERIPH_BATTERY_BALANCE_ID_DEFAULT36#define AP_PERIPH_BATTERY_BALANCE_ID_DEFAULT 037#endif383940const AP_Param::GroupInfo BattBalance::var_info[] {41// @Param: _NUM_CELLS42// @DisplayName: Number of battery cells43// @Description: Number of battery cells to monitor44// @Range: 0 6445AP_GROUPINFO("_NUM_CELLS", 1, BattBalance, num_cells, AP_PERIPH_BATTERY_BALANCE_NUMCELLS_DEFAULT),4647// @Param: _ID48// @DisplayName: Battery ID49// @Description: Battery ID to match against other batteries50// @Range: 0 12751AP_GROUPINFO("_ID", 2, BattBalance, id, AP_PERIPH_BATTERY_BALANCE_ID_DEFAULT),5253// @Param: _RATE54// @DisplayName: Send Rate55// @Description: Rate to send cell information56// @Range: 0 2057AP_GROUPINFO("_RATE", 3, BattBalance, rate, AP_PERIPH_BATTERY_BALANCE_RATE_DEFAULT),5859// @Param: _CELL1_PIN60// @DisplayName: First analog pin61// @Description: Analog pin of the first cell. Later cells must be sequential62// @Range: 0 12763AP_GROUPINFO("_CELL1_PIN", 4, BattBalance, cell1_pin, AP_PERIPH_BATTERY_BALANCE_CELL1_PIN_DEFAULT),6465AP_GROUPEND66};6768BattBalance::BattBalance(void)69{70AP_Param::setup_object_defaults(this, var_info);71}7273void AP_Periph_FW::batt_balance_update()74{75const int8_t ncell = battery_balance.num_cells;76if (ncell <= 0) {77return;78}7980// allocate cell sources if needed81if (battery_balance.cells == nullptr) {82battery_balance.cells = NEW_NOTHROW AP_HAL::AnalogSource*[ncell];83if (battery_balance.cells == nullptr) {84return;85}86battery_balance.cells_allocated = ncell;87for (uint8_t i=0; i<battery_balance.cells_allocated; i++) {88battery_balance.cells[i] = hal.analogin->channel(battery_balance.cell1_pin + i);89}90}9192const uint32_t now = AP_HAL::millis();93if (now - battery_balance.last_send_ms < 1000.0/battery_balance.rate.get()) {94return;95}96battery_balance.last_send_ms = now;9798// allocate space for the packet. This is a large99// packet that won't fit on the stack, so dynamically allocate100auto *pkt = NEW_NOTHROW ardupilot_equipment_power_BatteryInfoAux;101uint8_t *buffer = NEW_NOTHROW uint8_t[ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_MAX_SIZE];102if (pkt == nullptr || buffer == nullptr) {103delete pkt;104delete [] buffer;105return;106}107108pkt->voltage_cell.len = battery_balance.cells_allocated;109float last_cell = 0;110for (uint8_t i=0; i<battery_balance.cells_allocated; i++) {111auto *chan = battery_balance.cells[i];112if (chan == nullptr) {113continue;114}115const float v = chan->voltage_average();116pkt->voltage_cell.data[i] = v - last_cell;117last_cell = v;118}119pkt->max_current = nanf("");120pkt->nominal_voltage = nanf("");121pkt->battery_id = uint8_t(battery_balance.id);122123// encode and send message:124const uint16_t total_size = ardupilot_equipment_power_BatteryInfoAux_encode(pkt, buffer, !periph.canfdout());125126canard_broadcast(ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_SIGNATURE,127ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_ID,128CANARD_TRANSFER_PRIORITY_LOW,129buffer,130total_size);131132delete pkt;133delete [] buffer;134}135136#endif // HAL_PERIPH_ENABLE_BATTERY_BALANCE137138139140