parameter_update use uORB::Subscription consistently

This commit is contained in:
Daniel Agar
2019-07-28 11:55:52 -04:00
parent bbb96cbd0c
commit c8e59c4e39
47 changed files with 274 additions and 259 deletions
+7 -10
View File
@@ -55,7 +55,7 @@
#include <drivers/device/device.h>
#include <drivers/drv_hrt.h>
#include <arch/board/board.h>
#include <uORB/uORB.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/wind_estimate.h>
@@ -411,9 +411,7 @@ BottleDrop::task_main()
int vehicle_global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position));
struct parameter_update_s update;
memset(&update, 0, sizeof(update));
int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
uORB::Subscription parameter_update_sub{ORB_ID(parameter_update)};
struct mission_item_s flight_vector_s {};
struct mission_item_s flight_vector_e {};
@@ -492,12 +490,11 @@ BottleDrop::task_main()
orb_copy(ORB_ID(vehicle_global_position), vehicle_global_position_sub, &_global_pos);
}
// Get parameter updates
orb_check(parameter_update_sub, &updated);
if (updated) {
// copy global position
orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update);
// check for parameter updates
if (parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
parameter_update_sub.copy(&pupdate);
// update all parameters
param_get(param_gproperties, &z_0);
+13 -13
View File
@@ -54,6 +54,7 @@
#include <systemlib/err.h>
#include <parameters/param.h>
#include <perf/perf_counter.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/parameter_update.h>
@@ -326,15 +327,14 @@ int fixedwing_control_thread_main(int argc, char *argv[])
int manual_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
int global_sp_sub = orb_subscribe(ORB_ID(position_setpoint_triplet));
int param_sub = orb_subscribe(ORB_ID(parameter_update));
uORB::Subscription parameter_update_sub{ORB_ID(parameter_update)};
/* Setup of loop */
struct pollfd fds[2] = {};
fds[0].fd = param_sub;
struct pollfd fds[1] {};
fds[0].fd = att_sub;
fds[0].events = POLLIN;
fds[1].fd = att_sub;
fds[1].events = POLLIN;
while (!thread_should_exit) {
@@ -348,7 +348,7 @@ int fixedwing_control_thread_main(int argc, char *argv[])
* This design pattern makes the controller also agnostic of the attitude
* update speed - it runs as fast as the attitude updates with minimal latency.
*/
int ret = poll(fds, 2, 500);
int ret = poll(fds, 1, 500);
if (ret < 0) {
/*
@@ -361,18 +361,18 @@ int fixedwing_control_thread_main(int argc, char *argv[])
/* no return value = nothing changed for 500 ms, ignore */
} else {
/* only update parameters if they changed */
if (fds[0].revents & POLLIN) {
/* read from param to clear updated flag (uORB API requirement) */
struct parameter_update_s update;
orb_copy(ORB_ID(parameter_update), param_sub, &update);
// check for parameter updates
if (parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
parameter_update_sub.copy(&pupdate);
/* if a param update occured, re-read our parameters */
// if a param update occured, re-read our parameters
parameters_update(&ph, &p);
}
/* only run controller if attitude changed */
if (fds[1].revents & POLLIN) {
if (fds[0].revents & POLLIN) {
/* Check if there is a new position measurement or position setpoint */
+12 -16
View File
@@ -51,7 +51,7 @@
#include <poll.h>
#include <time.h>
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_attitude.h>
@@ -271,20 +271,16 @@ int rover_steering_control_thread_main(int argc, char *argv[])
int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
int param_sub = orb_subscribe(ORB_ID(parameter_update));
uORB::Subscription parameter_update_sub{ORB_ID(parameter_update)};
/* Setup of loop */
struct pollfd fds[2];
struct pollfd fds[1] {};
fds[0].fd = param_sub;
fds[0].fd = att_sub;
fds[0].events = POLLIN;
fds[1].fd = att_sub;
fds[1].events = POLLIN;
while (!thread_should_exit) {
/*
@@ -297,7 +293,7 @@ int rover_steering_control_thread_main(int argc, char *argv[])
* This design pattern makes the controller also agnostic of the attitude
* update speed - it runs as fast as the attitude updates with minimal latency.
*/
int ret = poll(fds, 2, 500);
int ret = poll(fds, 1, 500);
if (ret < 0) {
/*
@@ -310,18 +306,18 @@ int rover_steering_control_thread_main(int argc, char *argv[])
/* no return value = nothing changed for 500 ms, ignore */
} else {
/* only update parameters if they changed */
if (fds[0].revents & POLLIN) {
/* read from param to clear updated flag (uORB API requirement) */
struct parameter_update_s update;
orb_copy(ORB_ID(parameter_update), param_sub, &update);
// check for parameter updates
if (parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
parameter_update_sub.copy(&pupdate);
/* if a param update occured, re-read our parameters */
// if a param update occured, re-read our parameters
parameters_update(&ph, &pp);
}
/* only run controller if attitude changed */
if (fds[1].revents & POLLIN) {
if (fds[0].revents & POLLIN) {
/* Check if there is a new position measurement or position setpoint */