AP_BattMonitor: ignore SoC option for UAVCAN devices
This commit is contained in:
parent
eeb728237f
commit
40dbb316c1
@ -47,7 +47,7 @@ public:
|
||||
virtual bool has_temperature() const { return false; }
|
||||
|
||||
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
|
||||
uint8_t capacity_remaining_pct() const;
|
||||
virtual uint8_t capacity_remaining_pct() const;
|
||||
|
||||
// return true if cycle count can be provided and fills in cycles argument
|
||||
virtual bool get_cycle_count(uint16_t &cycles) const { return false; }
|
||||
|
@ -169,6 +169,13 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("BUS", 20, AP_BattMonitor_Params, _i2c_bus, 0),
|
||||
|
||||
// @Param: OPTIONS
|
||||
// @DisplayName: Battery monitor options
|
||||
// @Description: This sets options to change the behaviour of the battery monitor
|
||||
// @Bitmask: 1:IgnoreUAVCAN SoC
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("OPTIONS", 21, AP_BattMonitor_Params, _options, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
|
||||
};
|
||||
|
@ -17,6 +17,9 @@ public:
|
||||
BattMonitor_LowVoltageSource_Raw = 0,
|
||||
BattMonitor_LowVoltageSource_SagCompensated = 1
|
||||
};
|
||||
enum class Options : uint8_t {
|
||||
Ignore_UAVCAN_SoC = (1U<<0),
|
||||
};
|
||||
|
||||
BattMonitor_LowVoltage_Source failsafe_voltage_source(void) { return (enum BattMonitor_LowVoltage_Source)_failsafe_voltage_source.get(); }
|
||||
|
||||
@ -40,4 +43,5 @@ public:
|
||||
AP_Int32 _arming_minimum_capacity; /// capacity level required to arm
|
||||
AP_Float _arming_minimum_voltage; /// voltage level required to arm
|
||||
AP_Int8 _i2c_bus; /// I2C bus number
|
||||
AP_Int32 _options; /// Options
|
||||
};
|
||||
|
@ -90,6 +90,7 @@ void AP_BattMonitor_UAVCAN::handle_battery_info(const BattInfoCb &cb)
|
||||
_interim_state.temperature = cb.msg->temperature;
|
||||
_interim_state.voltage = cb.msg->voltage;
|
||||
_interim_state.current_amps = cb.msg->current;
|
||||
_soc = cb.msg->state_of_charge_pct;
|
||||
|
||||
uint32_t tnow = AP_HAL::micros();
|
||||
uint32_t dt = tnow - _interim_state.last_time_micros;
|
||||
@ -137,4 +138,16 @@ void AP_BattMonitor_UAVCAN::read()
|
||||
_state.healthy = _interim_state.healthy;
|
||||
}
|
||||
|
||||
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
|
||||
uint8_t AP_BattMonitor_UAVCAN::capacity_remaining_pct() const
|
||||
{
|
||||
if ((uint32_t(_params._options.get()) & uint32_t(AP_BattMonitor_Params::Options::Ignore_UAVCAN_SoC)) ||
|
||||
_soc > 100) {
|
||||
// a UAVCAN battery monitor may not be able to supply a state of charge. If it can't then
|
||||
// the user can set the option to use current integration in the backend instead.
|
||||
return AP_BattMonitor_Backend::capacity_remaining_pct();
|
||||
}
|
||||
return _soc;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -24,6 +24,9 @@ public:
|
||||
/// Read the battery voltage and current. Should be called at 10hz
|
||||
void read() override;
|
||||
|
||||
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
|
||||
uint8_t capacity_remaining_pct() const override;
|
||||
|
||||
bool has_current() const override {
|
||||
return true;
|
||||
}
|
||||
@ -47,4 +50,5 @@ private:
|
||||
|
||||
AP_UAVCAN* _ap_uavcan;
|
||||
uint8_t _node_id;
|
||||
uint8_t _soc;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user