Skip to content

Commit

Permalink
uORB: SubscriptionCallback cleanup naming
Browse files Browse the repository at this point in the history
  • Loading branch information
dagar committed Sep 28, 2019
1 parent 3f9b3fb commit fd67bd0
Showing 9 changed files with 29 additions and 28 deletions.
4 changes: 2 additions & 2 deletions src/lib/mixer_module/mixer_module.cpp
Original file line number Diff line number Diff line change
@@ -139,7 +139,7 @@ bool MixingOutput::updateSubscriptions(bool allow_wq_switch)
if (_groups_required & (1 << i)) {
PX4_DEBUG("subscribe to actuator_controls_%d", i);

if (!_control_subs[i].register_callback()) {
if (!_control_subs[i].registerCallback()) {
PX4_ERR("actuator_controls_%d register callback failed!", i);
}
}
@@ -205,7 +205,7 @@ void MixingOutput::setAllDisarmedValues(uint16_t value)
void MixingOutput::unregister()
{
for (auto &control_sub : _control_subs) {
control_sub.unregister_callback();
control_sub.unregisterCallback();
}
}

4 changes: 2 additions & 2 deletions src/modules/fw_att_control/FixedwingAttitudeControl.cpp
Original file line number Diff line number Diff line change
@@ -138,7 +138,7 @@ FixedwingAttitudeControl::~FixedwingAttitudeControl()
bool
FixedwingAttitudeControl::init()
{
if (!_att_sub.register_callback()) {
if (!_att_sub.registerCallback()) {
PX4_ERR("vehicle attitude callback registration failed!");
return false;
}
@@ -444,7 +444,7 @@ float FixedwingAttitudeControl::get_airspeed_and_update_scaling()
void FixedwingAttitudeControl::Run()
{
if (should_exit()) {
_att_sub.unregister_callback();
_att_sub.unregisterCallback();
exit_and_cleanup();
return;
}
4 changes: 2 additions & 2 deletions src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp
Original file line number Diff line number Diff line change
@@ -120,7 +120,7 @@ FixedwingPositionControl::~FixedwingPositionControl()
bool
FixedwingPositionControl::init()
{
if (!_global_pos_sub.register_callback()) {
if (!_global_pos_sub.registerCallback()) {
PX4_ERR("vehicle global position callback registration failed!");
return false;
}
@@ -1651,7 +1651,7 @@ void
FixedwingPositionControl::Run()
{
if (should_exit()) {
_global_pos_sub.unregister_callback();
_global_pos_sub.unregisterCallback();
exit_and_cleanup();
return;
}
4 changes: 2 additions & 2 deletions src/modules/mc_att_control/mc_att_control_main.cpp
Original file line number Diff line number Diff line change
@@ -90,7 +90,7 @@ MulticopterAttitudeControl::~MulticopterAttitudeControl()
bool
MulticopterAttitudeControl::init()
{
if (!_vehicle_angular_velocity_sub.register_callback()) {
if (!_vehicle_angular_velocity_sub.registerCallback()) {
PX4_ERR("vehicle_angular_velocity callback registration failed!");
return false;
}
@@ -520,7 +520,7 @@ void
MulticopterAttitudeControl::Run()
{
if (should_exit()) {
_vehicle_angular_velocity_sub.unregister_callback();
_vehicle_angular_velocity_sub.unregisterCallback();
exit_and_cleanup();
return;
}
10 changes: 5 additions & 5 deletions src/modules/sensors/vehicle_acceleration/VehicleAcceleration.cpp
Original file line number Diff line number Diff line change
@@ -69,7 +69,7 @@ VehicleAcceleration::Start()
SensorBiasUpdate(true);

// needed to change the active sensor if the primary stops updating
_sensor_selection_sub.register_callback();
_sensor_selection_sub.registerCallback();

return SensorCorrectionsUpdate(true);
}
@@ -81,10 +81,10 @@ VehicleAcceleration::Stop()

// clear all registered callbacks
for (auto &sub : _sensor_sub) {
sub.unregister_callback();
sub.unregisterCallback();
}

_sensor_selection_sub.unregister_callback();
_sensor_selection_sub.unregisterCallback();
}

void
@@ -132,12 +132,12 @@ VehicleAcceleration::SensorCorrectionsUpdate(bool force)
if (corrections.selected_accel_instance < MAX_SENSOR_COUNT) {
// clear all registered callbacks
for (auto &sub : _sensor_sub) {
sub.unregister_callback();
sub.unregisterCallback();
}

const int sensor_new = corrections.selected_accel_instance;

if (_sensor_sub[sensor_new].register_callback()) {
if (_sensor_sub[sensor_new].registerCallback()) {
PX4_DEBUG("selected sensor changed %d -> %d", _selected_sensor, sensor_new);
_selected_sensor = sensor_new;

Original file line number Diff line number Diff line change
@@ -69,7 +69,7 @@ VehicleAngularVelocity::Start()
SensorBiasUpdate(true);

// needed to change the active sensor if the primary stops updating
_sensor_selection_sub.register_callback();
_sensor_selection_sub.registerCallback();

return SensorCorrectionsUpdate(true);
}
@@ -81,10 +81,10 @@ VehicleAngularVelocity::Stop()

// clear all registered callbacks
for (auto &sub : _sensor_sub) {
sub.unregister_callback();
sub.unregisterCallback();
}

_sensor_selection_sub.unregister_callback();
_sensor_selection_sub.unregisterCallback();
}

void
@@ -143,11 +143,11 @@ VehicleAngularVelocity::SensorCorrectionsUpdate(bool force)
if (corrections.selected_gyro_instance < MAX_SENSOR_COUNT) {
// clear all registered callbacks
for (auto &sub : _sensor_control_sub) {
sub.unregister_callback();
sub.unregisterCallback();
}

for (auto &sub : _sensor_sub) {
sub.unregister_callback();
sub.unregisterCallback();
}

const int sensor_new = corrections.selected_gyro_instance;
@@ -159,7 +159,7 @@ VehicleAngularVelocity::SensorCorrectionsUpdate(bool force)
_sensor_control_sub[i].copy(&report);

if ((report.device_id != 0) && (report.device_id == _selected_sensor_device_id)) {
if (_sensor_control_sub[i].register_callback()) {
if (_sensor_control_sub[i].registerCallback()) {
PX4_DEBUG("selected sensor (control) changed %d -> %d", _selected_sensor, i);
_selected_sensor_control = i;

@@ -176,7 +176,7 @@ VehicleAngularVelocity::SensorCorrectionsUpdate(bool force)
// otherwise fallback to using sensor_gyro (legacy that will be removed)
_sensor_control_available = false;

if (_sensor_sub[sensor_new].register_callback()) {
if (_sensor_sub[sensor_new].registerCallback()) {
PX4_DEBUG("selected sensor changed %d -> %d", _selected_sensor, sensor_new);
_selected_sensor = sensor_new;

7 changes: 4 additions & 3 deletions src/modules/uORB/SubscriptionCallback.hpp
Original file line number Diff line number Diff line change
@@ -53,6 +53,7 @@ class SubscriptionCallback : public SubscriptionInterval, public ListNode<Subscr
* Constructor
*
* @param meta The uORB metadata (usually from the ORB_ID() macro) for the topic.
* @param interval_ms The requested maximum update interval in milliseconds.
* @param instance The instance for multi sub.
*/
SubscriptionCallback(const orb_metadata *meta, uint8_t interval_ms = 0, uint8_t instance = 0) :
@@ -62,10 +63,10 @@ class SubscriptionCallback : public SubscriptionInterval, public ListNode<Subscr

virtual ~SubscriptionCallback()
{
unregister_callback();
unregisterCallback();
};

bool register_callback()
bool registerCallback()
{
bool ret = false;

@@ -91,7 +92,7 @@ class SubscriptionCallback : public SubscriptionInterval, public ListNode<Subscr
return ret;
}

void unregister_callback()
void unregisterCallback()
{
if (_subscription.get_node()) {
_subscription.get_node()->unregister_callback(this);
2 changes: 1 addition & 1 deletion src/modules/uORB/SubscriptionInterval.hpp
Original file line number Diff line number Diff line change
@@ -137,7 +137,7 @@ class SubscriptionInterval

Subscription _subscription;
uint64_t _last_update{0}; // last update in microseconds
uint32_t _interval_us{0}; // maximum update interval in microseconds
uint32_t _interval_us{0}; // maximum update interval in microseconds

};

8 changes: 4 additions & 4 deletions src/modules/vtol_att_control/vtol_att_control_main.cpp
Original file line number Diff line number Diff line change
@@ -114,12 +114,12 @@ VtolAttitudeControl::~VtolAttitudeControl()
bool
VtolAttitudeControl::init()
{
if (!_actuator_inputs_mc.register_callback()) {
if (!_actuator_inputs_mc.registerCallback()) {
PX4_ERR("MC actuator controls callback registration failed!");
return false;
}

if (!_actuator_inputs_fw.register_callback()) {
if (!_actuator_inputs_fw.registerCallback()) {
PX4_ERR("FW actuator controls callback registration failed!");
return false;
}
@@ -290,8 +290,8 @@ void
VtolAttitudeControl::Run()
{
if (should_exit()) {
_actuator_inputs_fw.unregister_callback();
_actuator_inputs_mc.unregister_callback();
_actuator_inputs_fw.unregisterCallback();
_actuator_inputs_mc.unregisterCallback();
exit_and_cleanup();
return;
}

0 comments on commit fd67bd0

Please sign in to comment.