battery: delete unused armed

This commit is contained in:
Daniel Agar 2019-12-09 12:55:34 -05:00
parent 11bbc8ae34
commit de9e4dda4c
10 changed files with 16 additions and 33 deletions

View File

@ -411,7 +411,7 @@ Syslink::handle_message(syslink_message_t *msg)
memcpy(&vbat, &msg->data[1], sizeof(float));
//memcpy(&iset, &msg->data[5], sizeof(float));
_battery.updateBatteryStatus(t, vbat, -1, true, true, 0, 0, false, true);
_battery.updateBatteryStatus(t, vbat, -1, true, true, 0, 0, true);
// Update battery charge state

View File

@ -205,7 +205,7 @@ int DfBebopBusWrapper::_publish(struct bebop_state_data &data)
// TODO Check if this is the right way for the Bebop
// We don't have current measurements
_battery.updateBatteryStatus(timestamp, data.battery_voltage_v, 0.0, true, true, 0, _last_throttle, _armed, false);
_battery.updateBatteryStatus(timestamp, data.battery_voltage_v, 0.0, true, true, 0, _last_throttle, false);
esc_status_s esc_status = {};

View File

@ -141,7 +141,7 @@ int DfLtc2946Wrapper::_publish(const struct ltc2946_sensor_data &data)
_battery.updateBatteryStatus(t, data.battery_voltage_V, data.battery_current_A,
connected, true, 1,
ctrl.control[actuator_controls_s::INDEX_THROTTLE],
vcontrol_mode.flag_armed, true);
true);
return 0;
}

View File

@ -162,7 +162,7 @@ VOXLPM::measure()
switch (_ch_type) {
case VOXLPM_CH_TYPE_VBATT: {
_battery.updateBatteryStatus(tnow, _voltage, _amperage, true, true, 0, 0, false, true);
_battery.updateBatteryStatus(tnow, _voltage, _amperage, true, true, 0, 0, true);
}
// fallthrough
@ -183,7 +183,7 @@ VOXLPM::measure()
} else {
switch (_ch_type) {
case VOXLPM_CH_TYPE_VBATT: {
_battery.updateBatteryStatus(tnow, 0.0, 0.0, true, true, 0, 0, false, true);
_battery.updateBatteryStatus(tnow, 0.0, 0.0, true, true, 0, 0, true);
}
break;

View File

@ -117,8 +117,7 @@ Battery::reset()
void
Battery::updateBatteryStatus(hrt_abstime timestamp, float voltage_v, float current_a,
bool connected, bool selected_source, int priority,
float throttle_normalized,
bool armed, bool should_publish)
float throttle_normalized, bool should_publish)
{
reset();
_battery_status.timestamp = timestamp;
@ -126,7 +125,7 @@ Battery::updateBatteryStatus(hrt_abstime timestamp, float voltage_v, float curre
filterThrottle(throttle_normalized);
filterCurrent(current_a);
sumDischarged(timestamp, current_a);
estimateRemaining(_voltage_filtered_v, _current_filtered_a, _throttle_filtered, armed);
estimateRemaining(_voltage_filtered_v, _current_filtered_a, _throttle_filtered);
computeScale();
if (_battery_initialized) {
@ -235,7 +234,7 @@ Battery::sumDischarged(hrt_abstime timestamp, float current_a)
}
void
Battery::estimateRemaining(float voltage_v, float current_a, float throttle, bool armed)
Battery::estimateRemaining(float voltage_v, float current_a, float throttle)
{
// remaining battery capacity based on voltage
float cell_voltage = voltage_v / _params.n_cells;

View File

@ -96,11 +96,10 @@ public:
* @param selected_source: This battery is on the brick that the selected source for selected_source
* @param priority: The brick number -1. The term priority refers to the Vn connection on the LTC4417
* @param throttle_normalized: Throttle of the vehicle, between 0 and 1
* @param armed: Arming state of the vehicle
* @param should_publish If True, this function published a battery_status uORB message.
*/
void updateBatteryStatus(hrt_abstime timestamp, float voltage_v, float current_a, bool connected,
bool selected_source, int priority, float throttle_normalized, bool armed, bool should_publish);
bool selected_source, int priority, float throttle_normalized, bool should_publish);
/**
* Publishes the uORB battery_status message with the most recently-updated data.
@ -227,7 +226,7 @@ private:
void filterThrottle(float throttle);
void filterCurrent(float current_a);
void sumDischarged(hrt_abstime timestamp, float current_a);
void estimateRemaining(float voltage_v, float current_a, float throttle, bool armed);
void estimateRemaining(float voltage_v, float current_a, float throttle);
void determineWarning(bool connected);
void computeScale();

View File

@ -44,8 +44,7 @@ AnalogBattery::AnalogBattery(int index, ModuleParams *parent) :
void
AnalogBattery::updateBatteryStatusRawADC(hrt_abstime timestamp, int32_t voltage_raw, int32_t current_raw,
bool selected_source, int priority, float throttle_normalized,
bool armed)
bool selected_source, int priority, float throttle_normalized)
{
float voltage_v = (voltage_raw * _analog_params.cnt_v_volt) * _analog_params.v_div;
float current_a = ((current_raw * _analog_params.cnt_v_curr) - _analog_params.v_offs_cur) * _analog_params.a_per_v;
@ -55,7 +54,7 @@ AnalogBattery::updateBatteryStatusRawADC(hrt_abstime timestamp, int32_t voltage_
Battery::updateBatteryStatus(timestamp, voltage_v, current_a, connected,
selected_source, priority, throttle_normalized, armed, _params.source == 0);
selected_source, priority, throttle_normalized, _params.source == 0);
}
bool AnalogBattery::is_valid()
@ -144,4 +143,4 @@ AnalogBattery::updateParams()
}
Battery::updateParams();
}
}

View File

@ -50,11 +50,9 @@ public:
* @param selected_source This battery is on the brick that the selected source for selected_source
* @param priority: The brick number -1. The term priority refers to the Vn connection on the LTC4417
* @param throttle_normalized Throttle of the vehicle, between 0 and 1
* @param armed Arming state of the vehicle
*/
void updateBatteryStatusRawADC(hrt_abstime timestamp, int32_t voltage_raw, int32_t current_raw,
bool selected_source, int priority, float throttle_normalized,
bool armed);
bool selected_source, int priority, float throttle_normalized);
/**
* Whether the ADC channel for the voltage of this battery is valid.

View File

@ -59,7 +59,6 @@
#include <uORB/Subscription.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/battery_status.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
@ -130,11 +129,8 @@ public:
private:
DevHandle _h_adc; /**< ADC driver handle */
bool _armed{false}; /**< arming status of the vehicle */
uORB::Subscription _actuator_ctrl_0_sub{ORB_ID(actuator_controls_0)}; /**< attitude controls sub */
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; /**< notification of parameter updates */
uORB::Subscription _vcontrol_mode_sub{ORB_ID(vehicle_control_mode)}; /**< vehicle control mode subscription */
AnalogBattery _battery1;
@ -296,8 +292,7 @@ BatteryStatus::adc_poll()
bat_current_adc_readings[b],
selected_source == b,
b,
ctrl.control[actuator_controls_s::INDEX_THROTTLE],
_armed
ctrl.control[actuator_controls_s::INDEX_THROTTLE]
);
}
}
@ -318,13 +313,6 @@ BatteryStatus::Run()
perf_begin(_loop_perf);
/* check vehicle status for changes to publication state */
if (_vcontrol_mode_sub.updated()) {
vehicle_control_mode_s vcontrol_mode{};
_vcontrol_mode_sub.copy(&vcontrol_mode);
_armed = vcontrol_mode.flag_armed;
}
/* check parameters for updates */
parameter_update_poll();

View File

@ -370,7 +370,7 @@ void Simulator::handle_message_hil_sensor(const mavlink_message_t *msg)
vbatt *= _battery.cell_count();
const float throttle = 0.0f; // simulate no throttle compensation to make the estimate predictable
_battery.updateBatteryStatus(now_us, vbatt, ibatt, true, true, 0, throttle, armed, true);
_battery.updateBatteryStatus(now_us, vbatt, ibatt, true, true, 0, throttle, true);
_last_battery_timestamp = now_us;
}