forked from Archive/PX4-Autopilot
Compare commits
2 Commits
main
...
battery_pa
Author | SHA1 | Date |
---|---|---|
RomanBapst | 9b0873f528 | |
RomanBapst | 839ba751cc |
|
@ -113,6 +113,14 @@ void Battery::updateCurrent(const float current_a)
|
||||||
|
|
||||||
void Battery::updateBatteryStatus(const hrt_abstime ×tamp)
|
void Battery::updateBatteryStatus(const hrt_abstime ×tamp)
|
||||||
{
|
{
|
||||||
|
if (_parameter_update_sub.updated()) {
|
||||||
|
// Read from topic to clear updated flag
|
||||||
|
parameter_update_s parameter_update;
|
||||||
|
_parameter_update_sub.copy(¶meter_update);
|
||||||
|
|
||||||
|
updateParams();
|
||||||
|
}
|
||||||
|
|
||||||
if (!_battery_initialized) {
|
if (!_battery_initialized) {
|
||||||
_voltage_filter_v.reset(_voltage_v);
|
_voltage_filter_v.reset(_voltage_v);
|
||||||
_current_filter_a.reset(_current_a);
|
_current_filter_a.reset(_current_a);
|
||||||
|
|
|
@ -58,6 +58,10 @@
|
||||||
#include <uORB/topics/battery_status.h>
|
#include <uORB/topics/battery_status.h>
|
||||||
#include <uORB/topics/vehicle_status.h>
|
#include <uORB/topics/vehicle_status.h>
|
||||||
#include <uORB/topics/vehicle_thrust_setpoint.h>
|
#include <uORB/topics/vehicle_thrust_setpoint.h>
|
||||||
|
#include <uORB/SubscriptionInterval.hpp>
|
||||||
|
#include <uORB/topics/parameter_update.h>
|
||||||
|
|
||||||
|
using namespace time_literals;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* BatteryBase is a base class for any type of battery.
|
* BatteryBase is a base class for any type of battery.
|
||||||
|
@ -156,6 +160,7 @@ private:
|
||||||
uORB::Subscription _vehicle_thrust_setpoint_0_sub{ORB_ID(vehicle_thrust_setpoint)};
|
uORB::Subscription _vehicle_thrust_setpoint_0_sub{ORB_ID(vehicle_thrust_setpoint)};
|
||||||
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
|
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
|
||||||
uORB::PublicationMulti<battery_status_s> _battery_status_pub{ORB_ID(battery_status)};
|
uORB::PublicationMulti<battery_status_s> _battery_status_pub{ORB_ID(battery_status)};
|
||||||
|
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
|
||||||
|
|
||||||
bool _external_state_of_charge{false}; ///< inticates that the soc is injected and not updated by this library
|
bool _external_state_of_charge{false}; ///< inticates that the soc is injected and not updated by this library
|
||||||
|
|
||||||
|
|
|
@ -73,7 +73,7 @@ parameters:
|
||||||
max: 0.2
|
max: 0.2
|
||||||
decimal: 4
|
decimal: 4
|
||||||
increment: 0.0005
|
increment: 0.0005
|
||||||
reboot_required: true
|
reboot_required: false
|
||||||
num_instances: *max_num_config_instances
|
num_instances: *max_num_config_instances
|
||||||
instance_start: 1
|
instance_start: 1
|
||||||
default: [0.005, 0.005]
|
default: [0.005, 0.005]
|
||||||
|
@ -119,7 +119,7 @@ parameters:
|
||||||
max: 100000
|
max: 100000
|
||||||
decimal: 0
|
decimal: 0
|
||||||
increment: 50
|
increment: 50
|
||||||
reboot_required: true
|
reboot_required: false
|
||||||
num_instances: *max_num_config_instances
|
num_instances: *max_num_config_instances
|
||||||
instance_start: 1
|
instance_start: 1
|
||||||
default: [-1.0, -1.0]
|
default: [-1.0, -1.0]
|
||||||
|
|
Loading…
Reference in New Issue