Skip to content

Commit

Permalink
AP_BatteryMonitor: add current scaler for UAVCAN
Browse files Browse the repository at this point in the history
  • Loading branch information
Hwurzburg committed Jan 14, 2022
1 parent 21b7a8b commit 1a94157
Show file tree
Hide file tree
Showing 2 changed files with 18 additions and 3 deletions.
16 changes: 15 additions & 1 deletion libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,17 @@

extern const AP_HAL::HAL& hal;

const AP_Param::GroupInfo AP_BattMonitor_UAVCAN::var_info[] = {

// @Param: CUR_ADJUST
// @DisplayName: Adjusts current scale
// @Description: Scales all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
// @Range: .1 10
// @User: Advanced
AP_GROUPINFO("CUR_ADJUST", 27, AP_BattMonitor_UAVCAN, _cur_adjust, 1.0),
AP_GROUPEND
};

UC_REGISTRY_BINDER(BattInfoCb, uavcan::equipment::power::BatteryInfo);
UC_REGISTRY_BINDER(BattInfoAuxCb, ardupilot::equipment::power::BatteryInfoAux);
UC_REGISTRY_BINDER(MpptStreamCb, mppt::Stream);
Expand All @@ -30,6 +41,9 @@ AP_BattMonitor_UAVCAN::AP_BattMonitor_UAVCAN(AP_BattMonitor &mon, AP_BattMonitor
AP_BattMonitor_Backend(mon, mon_state, params),
_type(type)
{
AP_Param::setup_object_defaults(this,var_info);
_state.var_info = var_info;

// starts with not healthy
_state.healthy = false;
}
Expand Down Expand Up @@ -125,7 +139,7 @@ void AP_BattMonitor_UAVCAN::update_interim_state(const float voltage, const floa
WITH_SEMAPHORE(_sem_battmon);

_interim_state.voltage = voltage;
_interim_state.current_amps = current;
_interim_state.current_amps = _cur_adjust * current;
_soc = soc;

if (!isnanf(temperature_K) && temperature_K > 0) {
Expand Down
5 changes: 3 additions & 2 deletions libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@ class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend
/// Constructor
AP_BattMonitor_UAVCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_UAVCAN_Type type, AP_BattMonitor_Params &params);

static const struct AP_Param::GroupInfo var_info[];

void init() override {}

/// Read the battery voltage and current. Should be called at 10hz
Expand Down Expand Up @@ -54,7 +56,6 @@ class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend
private:
void handle_battery_info(const BattInfoCb &cb);
void handle_battery_info_aux(const BattInfoAuxCb &cb);

void update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc);

static bool match_battery_id(uint8_t instance, uint8_t battery_id) {
Expand Down Expand Up @@ -94,7 +95,7 @@ class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend
bool _has_battery_info_aux;
uint8_t _instance; // instance of this battery monitor
uavcan::Node<0> *_node; // UAVCAN node id

AP_Float _cur_adjust;
// MPPT variables
struct {
bool is_detected; // true if this UAVCAN device is a Packet Digital MPPT
Expand Down

0 comments on commit 1a94157

Please sign in to comment.