Browse Source

Removed all swapping of uORB instances

sbg
Timothy Scott 5 years ago committed by Lorenz Meier
parent
commit
4c1adc088f
  1. 8
      src/lib/battery/battery.cpp
  2. 9
      src/lib/battery/battery.h
  3. 14
      src/modules/battery_status/battery_status.cpp
  4. 17
      src/modules/commander/Commander.cpp
  5. 7
      src/modules/commander/Commander.hpp

8
src/lib/battery/battery.cpp

@ -165,14 +165,6 @@ Battery::publish()
orb_publish_auto(ORB_ID(battery_status), &_orb_advert, &_battery_status, &_orb_instance, ORB_PRIO_DEFAULT); orb_publish_auto(ORB_ID(battery_status), &_orb_advert, &_battery_status, &_orb_instance, ORB_PRIO_DEFAULT);
} }
void
Battery::swapUorbAdvert(Battery &other)
{
orb_advert_t tmp = _orb_advert;
_orb_advert = other._orb_advert;
other._orb_advert = tmp;
}
void void
Battery::filterVoltage(float voltage_v) Battery::filterVoltage(float voltage_v)
{ {

9
src/lib/battery/battery.h

@ -108,15 +108,6 @@ public:
*/ */
void publish(); void publish();
/**
* Some old functionality expects the primary battery to be published on instance 0. To maintain backwards
* compatibility, this function allows the advertisements (and therefore instances) of 2 batteries to be swapped.
* However, this should not be relied upon anywhere, and should be considered for all intents deprecated.
*
* The proper way to uniquely identify batteries is by the `id` field in the `battery_status` message.
*/
void swapUorbAdvert(Battery &other);
protected: protected:
struct { struct {
param_t v_empty; param_t v_empty;

14
src/modules/battery_status/battery_status.cpp

@ -117,10 +117,6 @@ private:
#endif #endif
}; // End _analogBatteries }; // End _analogBatteries
#if BOARD_NUMBER_BRICKS > 1
int _battery_pub_intance0ndx {0}; /**< track the index of instance 0 */
#endif /* BOARD_NUMBER_BRICKS > 1 */
perf_counter_t _loop_perf; /**< loop performance counter */ perf_counter_t _loop_perf; /**< loop performance counter */
/** /**
@ -210,17 +206,7 @@ BatteryStatus::adc_poll()
* VDD_5V_IN * VDD_5V_IN
*/ */
selected_source = b; selected_source = b;
# if BOARD_NUMBER_BRICKS > 1
/* Move the selected_source to instance 0 */
if (_battery_pub_intance0ndx != selected_source) {
_analogBatteries[_battery_pub_intance0ndx]->swapUorbAdvert(
*_analogBatteries[selected_source]
);
_battery_pub_intance0ndx = selected_source;
}
# endif /* BOARD_NUMBER_BRICKS > 1 */
} }
/* look for specific channels and process the raw voltage to measurement data */ /* look for specific channels and process the raw voltage to measurement data */

17
src/modules/commander/Commander.cpp

@ -3717,7 +3717,7 @@ void Commander::battery_status_check()
size_t num_connected_batteries = 0; size_t num_connected_batteries = 0;
for (int i = 0; i < ORB_MULTI_MAX_INSTANCES; i++) { for (size_t i = 0; i < sizeof(_battery_subs) / sizeof(_battery_subs[0]); i++) {
if (_battery_subs[i].updated() && _battery_subs[i].copy(&batteries[num_connected_batteries])) { if (_battery_subs[i].updated() && _battery_subs[i].copy(&batteries[num_connected_batteries])) {
// We need to update the status flag if ANY battery is updated, because the system source might have // We need to update the status flag if ANY battery is updated, because the system source might have
// changed, or might be nothing (if there is no battery connected) // changed, or might be nothing (if there is no battery connected)
@ -3729,15 +3729,15 @@ void Commander::battery_status_check()
} }
} }
/* update battery status */ if (!battery_sub_updated) {
if (battery_sub_updated) { // Nothing has changed since the last time this function was called, so nothing needs to be done now.
return;
}
// There are possibly multiple batteries, and we can't know which ones serve which purpose. So the safest // There are possibly multiple batteries, and we can't know which ones serve which purpose. So the safest
// option is to check if ANY of them have a warning, and specifically find which one has the most // option is to check if ANY of them have a warning, and specifically find which one has the most
// urgent warning. // urgent warning.
uint8_t worst_warning = battery_status_s::BATTERY_WARNING_NONE; uint8_t worst_warning = battery_status_s::BATTERY_WARNING_NONE;
// Sum the total current of all connected batteries. This is used to detect engine failure.
float total_current = 0;
// To make sure that all connected batteries are being regularly reported, we check which one has the // To make sure that all connected batteries are being regularly reported, we check which one has the
// oldest timestamp. // oldest timestamp.
hrt_abstime oldest_update = hrt_absolute_time(); hrt_abstime oldest_update = hrt_absolute_time();
@ -3752,7 +3752,9 @@ void Commander::battery_status_check()
oldest_update = batteries[i].timestamp; oldest_update = batteries[i].timestamp;
} }
total_current += batteries[i].current_filtered_a; if (batteries[i].system_source) {
_battery_current = batteries[i].current_filtered_a;
}
} }
bool battery_warning_level_increased_while_armed = false; bool battery_warning_level_increased_while_armed = false;
@ -3805,9 +3807,6 @@ void Commander::battery_status_check()
} }
} }
} }
_battery_current = total_current;
}
} }
void Commander::estimator_check() void Commander::estimator_check()

7
src/modules/commander/Commander.hpp

@ -43,7 +43,6 @@
#include <lib/mathlib/mathlib.h> #include <lib/mathlib/mathlib.h>
#include <px4_platform_common/module.h> #include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h> #include <px4_platform_common/module_params.h>
#include <containers/Array.hpp>
// publications // publications
#include <uORB/Publication.hpp> #include <uORB/Publication.hpp>
@ -375,12 +374,18 @@ private:
// Subscriptions // Subscriptions
uORB::Subscription _actuator_controls_sub{ORB_ID_VEHICLE_ATTITUDE_CONTROLS}; uORB::Subscription _actuator_controls_sub{ORB_ID_VEHICLE_ATTITUDE_CONTROLS};
#if BOARD_NUMBER_BRICKS > 1
uORB::Subscription _battery_subs[ORB_MULTI_MAX_INSTANCES] { uORB::Subscription _battery_subs[ORB_MULTI_MAX_INSTANCES] {
uORB::Subscription(ORB_ID(battery_status), 0), uORB::Subscription(ORB_ID(battery_status), 0),
uORB::Subscription(ORB_ID(battery_status), 1), uORB::Subscription(ORB_ID(battery_status), 1),
uORB::Subscription(ORB_ID(battery_status), 2), uORB::Subscription(ORB_ID(battery_status), 2),
uORB::Subscription(ORB_ID(battery_status), 3), uORB::Subscription(ORB_ID(battery_status), 3),
}; };
#else
uORB::Subscription _battery_subs[1] {
uORB::Subscription(ORB_ID(battery_status), 0)
};
#endif
uORB::Subscription _cmd_sub {ORB_ID(vehicle_command)}; uORB::Subscription _cmd_sub {ORB_ID(vehicle_command)};
uORB::Subscription _cpuload_sub{ORB_ID(cpuload)}; uORB::Subscription _cpuload_sub{ORB_ID(cpuload)};
uORB::Subscription _esc_status_sub{ORB_ID(esc_status)}; uORB::Subscription _esc_status_sub{ORB_ID(esc_status)};

Loading…
Cancel
Save