Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

update most parameter_update to uORB::Subscription consistently #12572

Merged
merged 1 commit into from
Sep 29, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 6 additions & 2 deletions src/drivers/heater/heater.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -292,9 +292,13 @@ float Heater::temperature_setpoint(char *argv[])

void Heater::update_params(const bool force)
{
parameter_update_s param_update;
// check for parameter updates
if (_parameter_update_sub.updated() || force) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);

if (_params_sub.update(&param_update) || force) {
// update parameters from storage
ModuleParams::updateParams();
}
}
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/heater/heater.h
Original file line number Diff line number Diff line change
Expand Up @@ -174,7 +174,7 @@ class Heater : public ModuleBase<Heater>, public ModuleParams, public px4::Sched

float _integrator_value = 0.0f;

uORB::Subscription _params_sub{ORB_ID(parameter_update)};
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};

float _proportional_value = 0.0f;

Expand Down
9 changes: 6 additions & 3 deletions src/drivers/lights/rgbled/rgbled.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,8 @@ class RGBLED : public device::I2C, public px4::ScheduledWorkItem
volatile bool _running{false};
volatile bool _should_run{true};
bool _leds_enabled{true};
uORB::Subscription _param_sub{ORB_ID(parameter_update)};

uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};

LedController _led_controller;

Expand Down Expand Up @@ -202,11 +203,13 @@ RGBLED::Run()
return;
}

if (_param_sub.updated()) {
// check for parameter updates
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_param_sub.copy(&pupdate);
_parameter_update_sub.copy(&pupdate);

// update parameters from storage
update_params();

// Immediately update to change brightness
Expand Down
9 changes: 6 additions & 3 deletions src/drivers/lights/rgbled_ncp5623c/rgbled_ncp5623c.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,8 @@ class RGBLED_NPC5623C : public device::I2C, public px4::ScheduledWorkItem
volatile bool _running{false};
volatile bool _should_run{true};
bool _leds_enabled{true};
uORB::Subscription _param_sub{ORB_ID(parameter_update)};

uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};

LedController _led_controller;

Expand Down Expand Up @@ -166,11 +167,13 @@ RGBLED_NPC5623C::Run()
return;
}

if (_param_sub.updated()) {
// check for parameter updates
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_param_sub.copy(&pupdate);
_parameter_update_sub.copy(&pupdate);

// update parameters from storage
update_params();

// Immediately update to change brightness
Expand Down
21 changes: 8 additions & 13 deletions src/drivers/linux_pwm_out/linux_pwm_out.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
#include <px4_getopt.h>
#include <px4_posix.h>

#include <uORB/uORB.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_armed.h>
Expand Down Expand Up @@ -260,7 +260,7 @@ void task_main(int argc, char *argv[])

Mixer::Airmode airmode = Mixer::Airmode::disabled;
update_params(airmode);
int params_sub = orb_subscribe(ORB_ID(parameter_update));
uORB::Subscription parameter_update_sub{ORB_ID(parameter_update)};

int rc_channels_sub = -1;

Expand Down Expand Up @@ -418,16 +418,15 @@ void task_main(int argc, char *argv[])
_task_should_exit = true;
}

/* check for parameter updates */
bool param_updated = false;
orb_check(params_sub, &param_updated);
// check for parameter updates
if (parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
parameter_update_sub.copy(&pupdate);

if (param_updated) {
struct parameter_update_s update;
orb_copy(ORB_ID(parameter_update), params_sub, &update);
// update parameters from storage
update_params(airmode);
}

}

delete pwm_out;
Expand All @@ -447,10 +446,6 @@ void task_main(int argc, char *argv[])
orb_unsubscribe(rc_channels_sub);
}

if (params_sub != -1) {
orb_unsubscribe(params_sub);
}

perf_free(_perf_control_latency);

_is_running = false;
Expand Down
17 changes: 9 additions & 8 deletions src/drivers/pwm_out_sim/PWMSim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,8 @@
#include <px4_time.h>
#include <mathlib/mathlib.h>

#include <uORB/Subscription.hpp>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/multirotor_motor_limits.h>

PWMSim::PWMSim() :
Expand Down Expand Up @@ -162,7 +164,7 @@ PWMSim::run()
_armed_sub = orb_subscribe(ORB_ID(actuator_armed));

update_params();
int params_sub = orb_subscribe(ORB_ID(parameter_update));
uORB::Subscription parameter_update_sub{ORB_ID(parameter_update)};

/* loop until killed */
while (!should_exit()) {
Expand Down Expand Up @@ -323,13 +325,13 @@ PWMSim::run()
}
}

/* check for parameter updates */
bool param_updated = false;
orb_check(params_sub, &param_updated);
// check for parameter updates
if (parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
parameter_update_sub.copy(&pupdate);

if (param_updated) {
struct parameter_update_s update;
orb_copy(ORB_ID(parameter_update), params_sub, &update);
// update parameters from storage
update_params();
}
}
Expand All @@ -341,7 +343,6 @@ PWMSim::run()
}

orb_unsubscribe(_armed_sub);
orb_unsubscribe(params_sub);
}

int
Expand Down
14 changes: 8 additions & 6 deletions src/drivers/px4fmu/fmu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@ class PX4FMU : public cdev::CDev, public ModuleBase<PX4FMU>, public OutputModule

unsigned _current_update_rate{0};

uORB::Subscription _param_sub{ORB_ID(parameter_update)};
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};


unsigned _num_outputs{0};
Expand Down Expand Up @@ -767,7 +767,13 @@ PX4FMU::Run()
update_pwm_out_state(pwm_on);
}

if (_param_sub.updated()) {
// check for parameter updates
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);

// update parameters from storage
update_params();
}

Expand All @@ -783,16 +789,12 @@ PX4FMU::Run()

void PX4FMU::update_params()
{
parameter_update_s pupdate;
_param_sub.update(&pupdate);

update_pwm_rev_mask();
update_pwm_trims();

updateParams();
}


int
PX4FMU::ioctl(file *filp, int cmd, unsigned long arg)
{
Expand Down
12 changes: 8 additions & 4 deletions src/drivers/px4io/px4io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -256,7 +256,7 @@ class PX4IO : public cdev::CDev
uORB::Subscription _t_actuator_controls_3{ORB_ID(actuator_controls_3)};; ///< actuator controls group 3 topic
uORB::Subscription _t_actuator_armed{ORB_ID(actuator_armed)}; ///< system armed control topic
uORB::Subscription _t_vehicle_control_mode{ORB_ID(vehicle_control_mode)}; ///< vehicle control mode topic
uORB::Subscription _t_param{ORB_ID(parameter_update)}; ///< parameter update topic
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; ///< parameter update topic
uORB::Subscription _t_vehicle_command{ORB_ID(vehicle_command)}; ///< vehicle command topic

bool _param_update_force; ///< force a parameter update
Expand Down Expand Up @@ -997,10 +997,14 @@ PX4IO::task_main()
*
* XXX this may be a bit spammy
*/
if (_t_param.updated() || _param_update_force) {
_param_update_force = false;

// check for parameter updates
if (_parameter_update_sub.updated() || _param_update_force) {
// clear update
parameter_update_s pupdate;
_t_param.copy(&pupdate);
_parameter_update_sub.copy(&pupdate);

_param_update_force = false;

if (!_rc_handling_disabled) {
/* re-upload RC input config as it may have changed */
Expand Down
17 changes: 8 additions & 9 deletions src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#include <cmath> // NAN
#include <string.h>

#include <uORB/uORB.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_armed.h>
Expand Down Expand Up @@ -357,7 +357,7 @@ void task_main(int argc, char *argv[])

Mixer::Airmode airmode = Mixer::Airmode::disabled;
update_params(airmode);
int params_sub = orb_subscribe(ORB_ID(parameter_update));
uORB::Subscription parameter_update_sub{ORB_ID(parameter_update)};

// Start disarmed
_armed.armed = false;
Expand Down Expand Up @@ -471,13 +471,13 @@ void task_main(int argc, char *argv[])
}
}

/* check for parameter updates */
bool param_updated = false;
orb_check(params_sub, &param_updated);
// check for parameter updates
if (parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
parameter_update_sub.copy(&pupdate);

if (param_updated) {
struct parameter_update_s update;
orb_copy(ORB_ID(parameter_update), params_sub, &update);
// update parameters from storage
update_params(airmode);
}
}
Expand All @@ -491,7 +491,6 @@ void task_main(int argc, char *argv[])
}

orb_unsubscribe(_armed_sub);
orb_unsubscribe(params_sub);

perf_free(_perf_control_latency);

Expand Down
20 changes: 10 additions & 10 deletions src/drivers/tap_esc/tap_esc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@
#include <lib/cdev/CDev.hpp>
#include <perf/perf_counter.h>
#include <px4_module_params.h>
#include <uORB/uORB.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_armed.h>
Expand Down Expand Up @@ -114,7 +114,9 @@ class TAP_ESC : public cdev::CDev, public ModuleBase<TAP_ESC>, public ModulePara
bool _is_armed = false;
int _armed_sub = -1;
int _test_motor_sub = -1;
int _params_sub = -1;

uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};

orb_advert_t _outputs_pub = nullptr;
actuator_outputs_s _outputs = {};
actuator_armed_s _armed = {};
Expand Down Expand Up @@ -191,7 +193,6 @@ TAP_ESC::~TAP_ESC()

orb_unsubscribe(_armed_sub);
orb_unsubscribe(_test_motor_sub);
orb_unsubscribe(_params_sub);

orb_unadvertise(_outputs_pub);
orb_unadvertise(_esc_feedback_pub);
Expand Down Expand Up @@ -336,7 +337,6 @@ int TAP_ESC::init()

_armed_sub = orb_subscribe(ORB_ID(actuator_armed));
_test_motor_sub = orb_subscribe(ORB_ID(test_motor));
_params_sub = orb_subscribe(ORB_ID(parameter_update));

return ret;
}
Expand Down Expand Up @@ -609,13 +609,13 @@ void TAP_ESC::cycle()

}

/* check for parameter updates */
bool param_updated = false;
orb_check(_params_sub, &param_updated);
// check for parameter updates
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);

if (param_updated) {
struct parameter_update_s update;
orb_copy(ORB_ID(parameter_update), _params_sub, &update);
// update parameters from storage
updateParams();
}
}
Expand Down
17 changes: 8 additions & 9 deletions src/drivers/uavcan/uavcan_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@
#include <arch/board/board.h>
#include <arch/chip/chip.h>

#include <uORB/Subscription.hpp>
#include <uORB/topics/esc_status.h>
#include <uORB/topics/parameter_update.h>

Expand Down Expand Up @@ -810,17 +811,17 @@ int UavcanNode::run()

update_params();

int params_sub = orb_subscribe(ORB_ID(parameter_update));
uORB::Subscription parameter_update_sub{ORB_ID(parameter_update)};

while (!_task_should_exit) {

/* check for parameter updates */
bool param_updated = false;
orb_check(params_sub, &param_updated);
// check for parameter updates
if (parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
parameter_update_sub.copy(&pupdate);

if (param_updated) {
struct parameter_update_s update;
orb_copy(ORB_ID(parameter_update), params_sub, &update);
// update parameters from storage
update_params();
}

Expand Down Expand Up @@ -995,8 +996,6 @@ int UavcanNode::run()
}
}

orb_unsubscribe(params_sub);

(void)::close(busevent_fd);

teardown();
Expand Down
Loading