diff --git a/src/drivers/dshot/DShot.cpp b/src/drivers/dshot/DShot.cpp index 06b4e336eb..62566e41c5 100644 --- a/src/drivers/dshot/DShot.cpp +++ b/src/drivers/dshot/DShot.cpp @@ -574,7 +574,7 @@ void DShot::Run() } } - if (_param_sub.updated()) { + if (_parameter_update_sub.updated()) { update_params(); } @@ -603,7 +603,7 @@ void DShot::Run() void DShot::update_params() { parameter_update_s pupdate; - _param_sub.update(&pupdate); + _parameter_update_sub.copy(&pupdate); updateParams(); diff --git a/src/drivers/dshot/DShot.h b/src/drivers/dshot/DShot.h index 15036b5bcc..b0519a247d 100644 --- a/src/drivers/dshot/DShot.h +++ b/src/drivers/dshot/DShot.h @@ -223,7 +223,7 @@ private: Mode _mode{MODE_NONE}; - uORB::Subscription _param_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; DEFINE_PARAMETERS( (ParamInt) _param_dshot_config, diff --git a/src/drivers/heater/heater.h b/src/drivers/heater/heater.h index 4dd72acd8d..882fc0e75b 100644 --- a/src/drivers/heater/heater.h +++ b/src/drivers/heater/heater.h @@ -46,12 +46,14 @@ #include #include #include -#include +#include #include #include #include +using namespace time_literals; + #define CONTROLLER_PERIOD_DEFAULT 100000 /** @@ -174,7 +176,7 @@ private: float _integrator_value = 0.0f; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; float _proportional_value = 0.0f; diff --git a/src/drivers/lights/rgbled/rgbled.cpp b/src/drivers/lights/rgbled/rgbled.cpp index 1f19544d86..d7f0063b34 100644 --- a/src/drivers/lights/rgbled/rgbled.cpp +++ b/src/drivers/lights/rgbled/rgbled.cpp @@ -49,8 +49,11 @@ #include #include #include +#include #include +using namespace time_literals; + #define ADDR 0x55 /**< I2C adress of TCA62724FMG */ #define SUB_ADDR_START 0x01 /**< write everything (with auto-increment) */ #define SUB_ADDR_PWM0 0x81 /**< blue (without auto-increment) */ @@ -61,6 +64,7 @@ #define SETTING_NOT_POWERSAVE 0x01 /**< power-save mode not off */ #define SETTING_ENABLE 0x02 /**< on */ + class RGBLED : public device::I2C, public I2CSPIDriver { public: @@ -88,11 +92,10 @@ private: uint8_t _b{0}; bool _leds_enabled{true}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; LedController _led_controller; - int send_led_enable(bool enable); int send_led_rgb(); int get(bool &on, bool &powersave, uint8_t &r, uint8_t &g, uint8_t &b); diff --git a/src/drivers/lights/rgbled_ncp5623c/rgbled_ncp5623c.cpp b/src/drivers/lights/rgbled_ncp5623c/rgbled_ncp5623c.cpp index 5a3225147e..6ee9ed53d3 100755 --- a/src/drivers/lights/rgbled_ncp5623c/rgbled_ncp5623c.cpp +++ b/src/drivers/lights/rgbled_ncp5623c/rgbled_ncp5623c.cpp @@ -47,9 +47,10 @@ #include #include #include -#include +#include #include +using namespace time_literals; #define ADDR 0x39 /**< I2C adress of NCP5623C */ @@ -89,7 +90,7 @@ private: volatile bool _should_run{true}; bool _leds_enabled{true}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; LedController _led_controller; diff --git a/src/drivers/linux_pwm_out/linux_pwm_out.cpp b/src/drivers/linux_pwm_out/linux_pwm_out.cpp index 884e53cb9f..ebf6d5c054 100644 --- a/src/drivers/linux_pwm_out/linux_pwm_out.cpp +++ b/src/drivers/linux_pwm_out/linux_pwm_out.cpp @@ -43,6 +43,7 @@ #include #include +#include #include #include #include @@ -63,6 +64,8 @@ #include "ocpoc_mmap.h" #include "bbblue_pwm_rc.h" +using namespace time_literals; + namespace linux_pwm_out { static px4_task_t _task_handle = -1; @@ -260,7 +263,7 @@ void task_main(int argc, char *argv[]) Mixer::Airmode airmode = Mixer::Airmode::disabled; update_params(airmode); - uORB::Subscription parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval parameter_update_sub{ORB_ID(parameter_update), 1_s}; int rc_channels_sub = -1; diff --git a/src/drivers/pca9685_pwm_out/main.cpp b/src/drivers/pca9685_pwm_out/main.cpp index 6eff589003..6522bb3de9 100644 --- a/src/drivers/pca9685_pwm_out/main.cpp +++ b/src/drivers/pca9685_pwm_out/main.cpp @@ -53,6 +53,7 @@ #define PCA9685_DEFAULT_ADDRESS (0x40) using namespace drv_pca9685_pwm; +using namespace time_literals; class PCA9685Wrapper : public cdev::CDev, public ModuleBase, public OutputModuleInterface { @@ -112,7 +113,7 @@ protected: PCA9685 *pca9685 = nullptr; // driver handle. - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; // param handle + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; MixingOutput _mixing_output{PCA9685_PWM_CHANNEL_COUNT, *this, MixingOutput::SchedulingPolicy::Disabled, true}; }; diff --git a/src/drivers/power_monitor/ina226/ina226.h b/src/drivers/power_monitor/ina226/ina226.h index edd24a5cde..58a377d908 100644 --- a/src/drivers/power_monitor/ina226/ina226.h +++ b/src/drivers/power_monitor/ina226/ina226.h @@ -45,8 +45,8 @@ #include #include #include -#include #include +#include #include #include #include @@ -207,7 +207,7 @@ private: Battery _battery; uORB::Subscription _actuators_sub{ORB_ID(actuator_controls_0)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; int read(uint8_t address, int16_t &data); int write(uint8_t address, uint16_t data); diff --git a/src/drivers/power_monitor/voxlpm/voxlpm.hpp b/src/drivers/power_monitor/voxlpm/voxlpm.hpp index d3a991efca..5717542ca8 100644 --- a/src/drivers/power_monitor/voxlpm/voxlpm.hpp +++ b/src/drivers/power_monitor/voxlpm/voxlpm.hpp @@ -89,6 +89,7 @@ #include #include +#include #include #include #include @@ -253,7 +254,7 @@ private: perf_counter_t _comms_errors; uORB::PublicationMulti _pm_pub_topic{ORB_ID(power_monitor)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; power_monitor_s _pm_status{}; diff --git a/src/drivers/pwm_out/PWMOut.hpp b/src/drivers/pwm_out/PWMOut.hpp index 4ebe17b8da..768d592cb1 100644 --- a/src/drivers/pwm_out/PWMOut.hpp +++ b/src/drivers/pwm_out/PWMOut.hpp @@ -169,8 +169,7 @@ private: unsigned _current_update_rate{0}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; - + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; unsigned _num_outputs{0}; int _class_instance{-1}; diff --git a/src/drivers/pwm_out_sim/PWMSim.hpp b/src/drivers/pwm_out_sim/PWMSim.hpp index c61262f79a..42a2d5dde4 100644 --- a/src/drivers/pwm_out_sim/PWMSim.hpp +++ b/src/drivers/pwm_out_sim/PWMSim.hpp @@ -44,6 +44,8 @@ #include #include +using namespace time_literals; + class PWMSim : public cdev::CDev, public ModuleBase, public OutputModuleInterface { public: @@ -76,7 +78,6 @@ private: static constexpr uint16_t PWM_SIM_PWM_MAX_MAGIC = 2000; MixingOutput _mixing_output{MAX_ACTUATORS, *this, MixingOutput::SchedulingPolicy::Auto, false, false}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; - + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; }; diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 60071d974e..5a79888d30 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -80,8 +80,8 @@ #include #include -#include #include +#include #include #include #include @@ -241,9 +241,10 @@ private: 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 _parameter_update_sub{ORB_ID(parameter_update)}; ///< parameter update topic uORB::Subscription _t_vehicle_command{ORB_ID(vehicle_command)}; ///< vehicle command topic + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + hrt_abstime _last_status_publish{0}; bool _param_update_force; ///< force a parameter update diff --git a/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp b/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp index 6a600339f2..3eb739ed0f 100644 --- a/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp +++ b/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp @@ -333,7 +333,7 @@ void task_main(int argc, char *argv[]) Mixer::Airmode airmode = Mixer::Airmode::disabled; update_params(airmode); - uORB::Subscription parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval parameter_update_sub{ORB_ID(parameter_update), 1_s}; // Start disarmed _armed.armed = false; diff --git a/src/drivers/tap_esc/tap_esc.cpp b/src/drivers/tap_esc/tap_esc.cpp index ce782f81c3..720d64c5bd 100644 --- a/src/drivers/tap_esc/tap_esc.cpp +++ b/src/drivers/tap_esc/tap_esc.cpp @@ -48,6 +48,7 @@ #include #include #include +#include #include #include #include @@ -78,6 +79,8 @@ # define TAP_ESC_CTRL_UORB_UPDATE_INTERVAL 2 // [ms] min: 2, max: 100 #endif +using namespace time_literals; + /* * This driver connects to TAP ESCs via serial. */ @@ -115,7 +118,7 @@ private: int _armed_sub = -1; int _test_motor_sub = -1; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; orb_advert_t _outputs_pub = nullptr; actuator_outputs_s _outputs = {}; diff --git a/src/drivers/uavcan/uavcan_main.hpp b/src/drivers/uavcan/uavcan_main.hpp index 2f05c4b83c..05df915679 100644 --- a/src/drivers/uavcan/uavcan_main.hpp +++ b/src/drivers/uavcan/uavcan_main.hpp @@ -68,8 +68,11 @@ #include #include +#include #include +using namespace time_literals; + class UavcanNode; /** @@ -215,7 +218,7 @@ private: bool _idle_throttle_when_armed{false}; int32_t _idle_throttle_when_armed_param{0}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; perf_counter_t _cycle_perf; perf_counter_t _interval_perf; diff --git a/src/drivers/uavcannode/UavcanNode.hpp b/src/drivers/uavcannode/UavcanNode.hpp index a3d4165b3e..2053b84c03 100644 --- a/src/drivers/uavcannode/UavcanNode.hpp +++ b/src/drivers/uavcannode/UavcanNode.hpp @@ -65,7 +65,6 @@ #include #include - #include #include @@ -79,6 +78,8 @@ #include #include +using namespace time_literals; + /** * A UAVCAN node. */ @@ -179,7 +180,7 @@ private: hrt_abstime _last_static_temperature_publish{0}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::SubscriptionCallbackWorkItem _battery_status_sub{this, ORB_ID(battery_status)}; uORB::SubscriptionCallbackWorkItem _diff_pressure_sub{this, ORB_ID(differential_pressure)}; diff --git a/src/examples/fixedwing_control/main.cpp b/src/examples/fixedwing_control/main.cpp index 08895a11ec..c16adbac27 100644 --- a/src/examples/fixedwing_control/main.cpp +++ b/src/examples/fixedwing_control/main.cpp @@ -55,6 +55,7 @@ #include #include #include +#include #include #include #include @@ -65,7 +66,8 @@ #include #include #include -#include + +using namespace time_literals; /* Prototypes */ @@ -315,7 +317,7 @@ int fixedwing_control_thread_main(int argc, char *argv[]) int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status)); int global_sp_sub = orb_subscribe(ORB_ID(position_setpoint_triplet)); - uORB::Subscription parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval parameter_update_sub{ORB_ID(parameter_update), 1_s}; /* Setup of loop */ diff --git a/src/examples/gyro_fft/GyroFFT.cpp b/src/examples/gyro_fft/GyroFFT.cpp index 17d8ef4043..accbd0e05d 100644 --- a/src/examples/gyro_fft/GyroFFT.cpp +++ b/src/examples/gyro_fft/GyroFFT.cpp @@ -38,7 +38,6 @@ #include using namespace matrix; -using namespace time_literals; using math::radians; GyroFFT::GyroFFT() : diff --git a/src/examples/gyro_fft/GyroFFT.hpp b/src/examples/gyro_fft/GyroFFT.hpp index 7a2905022b..9f19400e2c 100644 --- a/src/examples/gyro_fft/GyroFFT.hpp +++ b/src/examples/gyro_fft/GyroFFT.hpp @@ -54,6 +54,8 @@ #include "arm_math.h" #include "arm_const_structs.h" +using namespace time_literals; + class GyroFFT : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem { public: @@ -86,7 +88,8 @@ private: uORB::Publication _sensor_gyro_fft_pub{ORB_ID(sensor_gyro_fft)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _sensor_selection_sub{ORB_ID(sensor_selection)}; uORB::Subscription _vehicle_imu_status_sub{ORB_ID(vehicle_imu_status)}; diff --git a/src/examples/rover_steering_control/main.cpp b/src/examples/rover_steering_control/main.cpp index df51eb94b4..a1f8c6b47b 100644 --- a/src/examples/rover_steering_control/main.cpp +++ b/src/examples/rover_steering_control/main.cpp @@ -52,6 +52,7 @@ #include #include #include +#include #include #include #include @@ -70,6 +71,8 @@ /* process-specific header files */ #include "params.h" +using namespace time_literals; + /* Prototypes */ /** @@ -101,7 +104,7 @@ int parameters_init(struct param_handles *h); * Update all parameters * */ -int parameters_update(const struct param_handles *h, struct params *p); +int parameter_update(const struct param_handles *h, struct params *p); /** * Mainloop of daemon. @@ -141,7 +144,7 @@ int parameters_init(struct param_handles *h) return OK; } -int parameters_update(const struct param_handles *h, struct params *p) +int parameter_update(const struct param_handles *h, struct params *p) { param_get(h->yaw_p, &(p->yaw_p)); @@ -201,7 +204,7 @@ int rover_steering_control_thread_main(int argc, char *argv[]) /* initialize parameters, first the handles, then the values */ parameters_init(&ph); - parameters_update(&ph, &pp); + parameter_update(&ph, &pp); /* @@ -271,7 +274,7 @@ int rover_steering_control_thread_main(int argc, char *argv[]) int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); - uORB::Subscription parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval parameter_update_sub{ORB_ID(parameter_update), 1_s}; /* Setup of loop */ @@ -313,7 +316,7 @@ int rover_steering_control_thread_main(int argc, char *argv[]) parameter_update_sub.copy(&pupdate); // if a param update occured, re-read our parameters - parameters_update(&ph, &pp); + parameter_update(&ph, &pp); } /* only run controller if attitude changed */ diff --git a/src/modules/airship_att_control/airship_att_control.hpp b/src/modules/airship_att_control/airship_att_control.hpp index 326785cca2..201d791c06 100644 --- a/src/modules/airship_att_control/airship_att_control.hpp +++ b/src/modules/airship_att_control/airship_att_control.hpp @@ -42,6 +42,8 @@ #include #include +using namespace time_literals; + /** * Airship attitude control app start / stop handling function */ @@ -80,7 +82,7 @@ private: void publish_actuator_controls(); - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; /**< parameter updates subscription */ + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; /**< parameter updates subscription */ uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; /**< vehicle status subscription */ uORB::Subscription _manual_control_sp_sub{ORB_ID(manual_control_setpoint)}; /**< manual control setpoint subscription */ diff --git a/src/modules/airspeed_selector/airspeed_selector_main.cpp b/src/modules/airspeed_selector/airspeed_selector_main.cpp index dcbb1fca38..405be0c30e 100644 --- a/src/modules/airspeed_selector/airspeed_selector_main.cpp +++ b/src/modules/airspeed_selector/airspeed_selector_main.cpp @@ -106,9 +106,10 @@ private: uORB::PublicationMulti _wind_est_pub[MAX_NUM_AIRSPEED_SENSORS + 1] {{ORB_ID(wind_estimate)}, {ORB_ID(wind_estimate)}, {ORB_ID(wind_estimate)}, {ORB_ID(wind_estimate)}}; /**< wind estimate topic (for each airspeed validator + purely sideslip fusion) */ orb_advert_t _mavlink_log_pub {nullptr}; /**< mavlink log topic*/ + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _estimator_selector_status_sub{ORB_ID(estimator_selector_status)}; uORB::Subscription _estimator_status_sub{ORB_ID(estimator_status)}; - uORB::Subscription _param_sub{ORB_ID(parameter_update)}; uORB::Subscription _vehicle_acceleration_sub{ORB_ID(vehicle_acceleration)}; uORB::Subscription _vehicle_air_data_sub{ORB_ID(vehicle_air_data)}; uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; @@ -283,7 +284,7 @@ AirspeedModule::Run() parameter_update_s update; - if (_param_sub.update(&update)) { + if (_parameter_update_sub.update(&update)) { update_params(); } diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp index ce90d2a7e1..70b48398c8 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp @@ -108,7 +108,7 @@ private: uORB::SubscriptionCallbackWorkItem _sensors_sub{this, ORB_ID(sensor_combined)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::Subscription _gps_sub{ORB_ID(vehicle_gps_position)}; uORB::Subscription _local_position_sub{ORB_ID(vehicle_local_position)}; uORB::Subscription _vision_odom_sub{ORB_ID(vehicle_visual_odometry)}; diff --git a/src/modules/battery_status/battery_status.cpp b/src/modules/battery_status/battery_status.cpp index a3aaf1b5b2..a509a3fea0 100644 --- a/src/modules/battery_status/battery_status.cpp +++ b/src/modules/battery_status/battery_status.cpp @@ -101,7 +101,7 @@ private: void Run() override; uORB::Subscription _actuator_ctrl_0_sub{ORB_ID(actuator_controls_0)}; /**< attitude controls sub */ - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; /**< notification of parameter updates */ + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; /**< notification of parameter updates */ uORB::SubscriptionCallbackWorkItem _adc_report_sub{this, ORB_ID(adc_report)}; static constexpr uint32_t SAMPLE_FREQUENCY_HZ = 100; diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index 58861d2ac3..608bbfa48e 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -403,7 +403,6 @@ private: uORB::Subscription _geofence_result_sub{ORB_ID(geofence_result)}; uORB::Subscription _iridiumsbd_status_sub{ORB_ID(iridiumsbd_status)}; uORB::Subscription _land_detector_sub{ORB_ID(vehicle_land_detected)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _safety_sub{ORB_ID(safety)}; uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; uORB::Subscription _manual_control_switches_sub{ORB_ID(manual_control_switches)}; @@ -411,6 +410,8 @@ private: uORB::Subscription _vehicle_acceleration_sub{ORB_ID(vehicle_acceleration)}; uORB::Subscription _vtol_vehicle_status_sub{ORB_ID(vtol_vehicle_status)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::SubscriptionMultiArray _battery_status_subs{ORB_ID::battery_status}; uORB::SubscriptionMultiArray _distance_sensor_subs{ORB_ID::distance_sensor}; uORB::SubscriptionMultiArray _telemetry_status_subs{ORB_ID::telemetry_status}; diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index c6d2911abd..ba9122470d 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -208,6 +208,8 @@ private: float _airspeed_scale_factor{1.0f}; ///< scale factor correction applied to airspeed measurements + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _airdata_sub{ORB_ID(vehicle_air_data)}; uORB::Subscription _airspeed_sub{ORB_ID(airspeed)}; uORB::Subscription _distance_sensor_sub{ORB_ID(distance_sensor)}; @@ -215,7 +217,6 @@ private: uORB::Subscription _landing_target_pose_sub{ORB_ID(landing_target_pose)}; uORB::Subscription _magnetometer_sub{ORB_ID(vehicle_magnetometer)}; uORB::Subscription _optical_flow_sub{ORB_ID(optical_flow)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _sensor_selection_sub{ORB_ID(sensor_selection)}; uORB::Subscription _status_sub{ORB_ID(vehicle_status)}; uORB::Subscription _vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)}; diff --git a/src/modules/ekf2/EKF2Selector.hpp b/src/modules/ekf2/EKF2Selector.hpp index 6663b273c1..3ec29a7bb6 100644 --- a/src/modules/ekf2/EKF2Selector.hpp +++ b/src/modules/ekf2/EKF2Selector.hpp @@ -181,7 +181,7 @@ private: uint8_t _lat_lon_reset_counter{0}; uint8_t _alt_reset_counter{0}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::Subscription _sensors_status_imu{ORB_ID(sensors_status_imu)}; // Publications diff --git a/src/modules/esc_battery/EscBattery.hpp b/src/modules/esc_battery/EscBattery.hpp index 0c2a6cc8b1..dc0ae3ac11 100644 --- a/src/modules/esc_battery/EscBattery.hpp +++ b/src/modules/esc_battery/EscBattery.hpp @@ -71,7 +71,7 @@ private: void parameters_updated(); - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::Subscription _actuator_ctrl_0_sub{ORB_ID(actuator_controls_0)}; uORB::SubscriptionCallbackWorkItem _esc_status_sub{this, ORB_ID(esc_status)}; diff --git a/src/modules/flight_mode_manager/FlightModeManager.hpp b/src/modules/flight_mode_manager/FlightModeManager.hpp index 335d88e93d..2af397363d 100644 --- a/src/modules/flight_mode_manager/FlightModeManager.hpp +++ b/src/modules/flight_mode_manager/FlightModeManager.hpp @@ -94,8 +94,9 @@ private: perf_counter_t _loop_perf; ///< loop duration performance counter hrt_abstime _time_stamp_last_loop{0}; ///< time stamp of last loop iteration + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::SubscriptionData _home_position_sub{ORB_ID(home_position)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _vehicle_attitude_setpoint_sub{ORB_ID(vehicle_attitude_setpoint)}; uORB::SubscriptionData _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; uORB::SubscriptionData _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)}; diff --git a/src/modules/fw_att_control/FixedwingAttitudeControl.hpp b/src/modules/fw_att_control/FixedwingAttitudeControl.hpp index 1372e070ab..3a22a0bc58 100644 --- a/src/modules/fw_att_control/FixedwingAttitudeControl.hpp +++ b/src/modules/fw_att_control/FixedwingAttitudeControl.hpp @@ -72,6 +72,8 @@ using matrix::Quatf; using uORB::SubscriptionData; +using namespace time_literals; + class FixedwingAttitudeControl final : public ModuleBase, public ModuleParams, public px4::WorkItem { @@ -95,11 +97,12 @@ private: uORB::SubscriptionCallbackWorkItem _att_sub{this, ORB_ID(vehicle_attitude)}; /**< vehicle attitude */ + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _att_sp_sub{ORB_ID(vehicle_attitude_setpoint)}; /**< vehicle attitude setpoint */ uORB::Subscription _battery_status_sub{ORB_ID(battery_status)}; /**< battery status subscription */ uORB::Subscription _local_pos_sub{ORB_ID(vehicle_local_position)}; /**< local position subscription */ uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; /**< notification of manual control updates */ - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; /**< notification of parameter updates */ uORB::Subscription _rates_sp_sub{ORB_ID(vehicle_rates_setpoint)}; /**< vehicle rates setpoint */ uORB::Subscription _vcontrol_mode_sub{ORB_ID(vehicle_control_mode)}; /**< vehicle status subscription */ uORB::Subscription _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)}; /**< vehicle land detected subscription */ diff --git a/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp b/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp index a7b21a8511..66403a435d 100644 --- a/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp +++ b/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp @@ -148,10 +148,11 @@ private: uORB::SubscriptionCallbackWorkItem _local_pos_sub{this, ORB_ID(vehicle_local_position)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _control_mode_sub{ORB_ID(vehicle_control_mode)}; ///< control mode subscription uORB::Subscription _global_pos_sub{ORB_ID(vehicle_global_position)}; uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; ///< notification of manual control updates - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; ///< notification of parameter updates uORB::Subscription _pos_sp_triplet_sub{ORB_ID(position_setpoint_triplet)}; uORB::Subscription _vehicle_air_data_sub{ORB_ID(vehicle_air_data)}; uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; ///< vehicle attitude subscription diff --git a/src/modules/land_detector/LandDetector.h b/src/modules/land_detector/LandDetector.h index dc78c23935..2592e00bdd 100644 --- a/src/modules/land_detector/LandDetector.h +++ b/src/modules/land_detector/LandDetector.h @@ -169,8 +169,9 @@ private: uORB::Publication _vehicle_land_detected_pub{ORB_ID(vehicle_land_detected)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _actuator_armed_sub{ORB_ID(actuator_armed)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _vehicle_acceleration_sub{ORB_ID(vehicle_acceleration)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; diff --git a/src/modules/landing_target_estimator/LandingTargetEstimator.cpp b/src/modules/landing_target_estimator/LandingTargetEstimator.cpp index b9e9dc5882..bc0249a3ca 100644 --- a/src/modules/landing_target_estimator/LandingTargetEstimator.cpp +++ b/src/modules/landing_target_estimator/LandingTargetEstimator.cpp @@ -225,14 +225,10 @@ void LandingTargetEstimator::update() void LandingTargetEstimator::_check_params(const bool force) { - bool updated = _parameterSub.updated(); + if (_parameter_update_sub.updated() || force) { + parameter_update_s pupdate; + _parameter_update_sub.copy(&pupdate); - if (updated) { - parameter_update_s paramUpdate; - _parameterSub.copy(¶mUpdate); - } - - if (updated || force) { _update_params(); } } diff --git a/src/modules/landing_target_estimator/LandingTargetEstimator.h b/src/modules/landing_target_estimator/LandingTargetEstimator.h index 2fa556c3b2..55a2d47cb1 100644 --- a/src/modules/landing_target_estimator/LandingTargetEstimator.h +++ b/src/modules/landing_target_estimator/LandingTargetEstimator.h @@ -47,6 +47,7 @@ #include #include #include +#include #include #include #include @@ -59,6 +60,7 @@ #include #include "KalmanFilter.h" +using namespace time_literals; namespace landing_target_estimator { @@ -96,7 +98,7 @@ protected: uORB::Publication _targetInnovationsPub{ORB_ID(landing_target_innovations)}; landing_target_innovations_s _target_innovations{}; - uORB::Subscription _parameterSub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; private: diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp index 86b10794d4..0c783dba60 100644 --- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp +++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp @@ -241,7 +241,7 @@ void BlockLocalPositionEstimator::Run() _lastArmedState = armedState; // see which updates are available - bool paramsUpdated = _sub_param_update.update(); + const bool paramsUpdated = _parameter_update_sub.updated(); _baroUpdated = false; if ((_param_lpe_fusion.get() & FUSE_BARO) && _sub_airdata.update()) { @@ -266,6 +266,10 @@ void BlockLocalPositionEstimator::Run() // update parameters if (paramsUpdated) { + // clear update + parameter_update_s pupdate; + _parameter_update_sub.copy(&pupdate); + SuperBlock::updateParams(); ModuleParams::updateParams(); updateSSParams(); diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp index 690fcc5a19..0302e5ec65 100644 --- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp +++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp @@ -263,12 +263,13 @@ private: // subscriptions uORB::SubscriptionCallbackWorkItem _sensors_sub{this, ORB_ID(sensor_combined)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::SubscriptionData _sub_armed{ORB_ID(actuator_armed)}; uORB::SubscriptionData _sub_land{ORB_ID(vehicle_land_detected)}; uORB::SubscriptionData _sub_att{ORB_ID(vehicle_attitude)}; uORB::SubscriptionData _sub_angular_velocity{ORB_ID(vehicle_angular_velocity)}; uORB::SubscriptionData _sub_flow{ORB_ID(optical_flow)}; - uORB::SubscriptionData _sub_param_update{ORB_ID(parameter_update)}; uORB::SubscriptionData _sub_gps{ORB_ID(vehicle_gps_position)}; uORB::SubscriptionData _sub_visual_odom{ORB_ID(vehicle_visual_odometry)}; uORB::SubscriptionData _sub_mocap_odom{ORB_ID(vehicle_mocap_odometry)}; diff --git a/src/modules/logger/logger.h b/src/modules/logger/logger.h index 120be110c3..01129dfbba 100644 --- a/src/modules/logger/logger.h +++ b/src/modules/logger/logger.h @@ -353,8 +353,8 @@ private: uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; - uORB::SubscriptionInterval _log_message_sub{ORB_ID(log_message), 20}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _log_message_sub{ORB_ID(log_message), 20}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; DEFINE_PARAMETERS( (ParamInt) _param_sdlog_utc_offset, diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index d763ed5e66..c68f8f965c 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -52,7 +52,6 @@ #include #include #include -#include #include "mavlink_receiver.h" #include "mavlink_main.h" @@ -2136,8 +2135,6 @@ Mavlink::task_main(int argc, char *argv[]) pthread_mutex_init(&_message_buffer_mutex, nullptr); } - uORB::Subscription parameter_update_sub{ORB_ID(parameter_update)}; - uORB::Subscription cmd_sub{ORB_ID(vehicle_command)}; // ensure topic exists, otherwise we might lose first queued commands (leading to printf error's below) orb_advertise_queue(ORB_ID(vehicle_command), nullptr, vehicle_command_s::ORB_QUEUE_LENGTH); @@ -2247,10 +2244,10 @@ Mavlink::task_main(int argc, char *argv[]) update_rate_mult(); // check for parameter updates - if (parameter_update_sub.updated()) { + if (_parameter_update_sub.updated()) { // clear update parameter_update_s pupdate; - parameter_update_sub.copy(&pupdate); + _parameter_update_sub.copy(&pupdate); // update parameters from storage mavlink_update_parameters(); diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 93c6d7e153..491ee1758a 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -69,8 +69,10 @@ #include #include #include +#include #include -#include +#include +#include #include #include @@ -530,6 +532,8 @@ private: uORB::PublicationMulti _telem_status_pub{ORB_ID(telemetry_status)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + bool _task_running{true}; static bool _boot_complete; static constexpr int MAVLINK_MAX_INSTANCES{4}; diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index a20035172b..6f356f71bc 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -354,14 +354,14 @@ MavlinkParametersManager::send_untransmitted() { bool sent_one = false; - if (_mavlink_parameter_sub.updated()) { - // Clear the ready flag - parameter_update_s value; - _mavlink_parameter_sub.update(&value); + if (_parameter_update_sub.updated()) { + // clear the update + parameter_update_s pupdate; + _parameter_update_sub.copy(&pupdate); // Schedule an update if not already the case if (_param_update_time == 0) { - _param_update_time = value.timestamp; + _param_update_time = pupdate.timestamp; _param_update_index = 0; } } diff --git a/src/modules/mavlink/mavlink_parameters.h b/src/modules/mavlink/mavlink_parameters.h index a71657f1d6..d55ed8e029 100644 --- a/src/modules/mavlink/mavlink_parameters.h +++ b/src/modules/mavlink/mavlink_parameters.h @@ -47,12 +47,15 @@ #include "mavlink_bridge_header.h" #include #include +#include #include #include #include #include #include +using namespace time_literals; + class Mavlink; class MavlinkParametersManager @@ -147,7 +150,7 @@ protected: uORB::Subscription _uavcan_parameter_value_sub{ORB_ID(uavcan_parameter_value)}; - uORB::Subscription _mavlink_parameter_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; hrt_abstime _param_update_time{0}; int _param_update_index{0}; diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index b7f733aabe..3104ed95cb 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -55,6 +55,7 @@ #include #include #include +#include #include #include #include @@ -107,6 +108,8 @@ # include #endif // !CONSTRAINED_FLASH +using namespace time_literals; + class Mavlink; class MavlinkReceiver : public ModuleParams @@ -304,11 +307,12 @@ private: // ORB subscriptions uORB::Subscription _actuator_armed_sub{ORB_ID(actuator_armed)}; uORB::Subscription _control_mode_sub{ORB_ID(vehicle_control_mode)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)}; uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + // hil_sensor and hil_state_quaternion enum SensorSource { ACCEL = 0b111, diff --git a/src/modules/mavlink/streams/HIGH_LATENCY2.hpp b/src/modules/mavlink/streams/HIGH_LATENCY2.hpp index cf7b6f7915..cee6010bc4 100644 --- a/src/modules/mavlink/streams/HIGH_LATENCY2.hpp +++ b/src/modules/mavlink/streams/HIGH_LATENCY2.hpp @@ -46,6 +46,7 @@ #include #include #include +#include #include #include #include diff --git a/src/modules/mc_att_control/mc_att_control.hpp b/src/modules/mc_att_control/mc_att_control.hpp index 589ee046c7..41b4e3a95e 100644 --- a/src/modules/mc_att_control/mc_att_control.hpp +++ b/src/modules/mc_att_control/mc_att_control.hpp @@ -58,6 +58,8 @@ #include +using namespace time_literals; + /** * Multicopter attitude control app start / stop handling function */ @@ -98,10 +100,11 @@ private: AttitudeControl _attitude_control; ///< class for attitude control calculations + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _vehicle_attitude_setpoint_sub{ORB_ID(vehicle_attitude_setpoint)}; uORB::Subscription _v_rates_sp_sub{ORB_ID(vehicle_rates_setpoint)}; /**< vehicle rates setpoint subscription */ uORB::Subscription _v_control_mode_sub{ORB_ID(vehicle_control_mode)}; /**< vehicle control mode subscription */ - uORB::Subscription _params_sub{ORB_ID(parameter_update)}; /**< parameter updates subscription */ uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; /**< manual control setpoint subscription */ uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; /**< vehicle status subscription */ uORB::Subscription _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)}; /**< vehicle land detected subscription */ diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 08ab125356..c1a7327047 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -228,10 +228,10 @@ MulticopterAttitudeControl::Run() perf_begin(_loop_perf); // Check if parameters have changed - if (_params_sub.updated()) { + if (_parameter_update_sub.updated()) { // clear update parameter_update_s param_update; - _params_sub.copy(¶m_update); + _parameter_update_sub.copy(¶m_update); updateParams(); parameters_updated(); diff --git a/src/modules/mc_hover_thrust_estimator/MulticopterHoverThrustEstimator.hpp b/src/modules/mc_hover_thrust_estimator/MulticopterHoverThrustEstimator.hpp index a66c289df1..6f6280e115 100644 --- a/src/modules/mc_hover_thrust_estimator/MulticopterHoverThrustEstimator.hpp +++ b/src/modules/mc_hover_thrust_estimator/MulticopterHoverThrustEstimator.hpp @@ -61,6 +61,8 @@ #include "zero_order_hover_thrust_ekf.hpp" +using namespace time_literals; + class MulticopterHoverThrustEstimator : public ModuleBase, public ModuleParams, public px4::WorkItem { @@ -97,7 +99,8 @@ private: uORB::SubscriptionCallbackWorkItem _vehicle_local_position_sub{this, ORB_ID(vehicle_local_position)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; uORB::Subscription _vehicle_local_position_setpoint_sub{ORB_ID(vehicle_local_position_setpoint)}; diff --git a/src/modules/mc_pos_control/MulticopterPositionControl.hpp b/src/modules/mc_pos_control/MulticopterPositionControl.hpp index 8b9fc8d606..7ef50bdfbe 100644 --- a/src/modules/mc_pos_control/MulticopterPositionControl.hpp +++ b/src/modules/mc_pos_control/MulticopterPositionControl.hpp @@ -92,8 +92,9 @@ private: uORB::SubscriptionCallbackWorkItem _local_pos_sub{this, ORB_ID(vehicle_local_position)}; /**< vehicle local position */ + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _control_mode_sub{ORB_ID(vehicle_control_mode)}; /**< vehicle control mode subscription */ - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; /**< notification of parameter updates */ uORB::Subscription _hover_thrust_estimate_sub{ORB_ID(hover_thrust_estimate)}; uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; uORB::Subscription _vehicle_constraints_sub{ORB_ID(vehicle_constraints)}; diff --git a/src/modules/mc_rate_control/MulticopterRateControl.hpp b/src/modules/mc_rate_control/MulticopterRateControl.hpp index f21982963a..6816848013 100644 --- a/src/modules/mc_rate_control/MulticopterRateControl.hpp +++ b/src/modules/mc_rate_control/MulticopterRateControl.hpp @@ -60,6 +60,8 @@ #include #include +using namespace time_literals; + class MulticopterRateControl : public ModuleBase, public ModuleParams, public px4::WorkItem { public: @@ -91,13 +93,14 @@ private: uORB::Subscription _landing_gear_sub{ORB_ID(landing_gear)}; uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; uORB::Subscription _motor_limits_sub{ORB_ID(multirotor_motor_limits)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _v_control_mode_sub{ORB_ID(vehicle_control_mode)}; uORB::Subscription _v_rates_sp_sub{ORB_ID(vehicle_rates_setpoint)}; uORB::Subscription _vehicle_angular_acceleration_sub{ORB_ID(vehicle_angular_acceleration)}; uORB::Subscription _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::SubscriptionCallbackWorkItem _vehicle_angular_velocity_sub{this, ORB_ID(vehicle_angular_velocity)}; uORB::Publication _actuators_0_pub; diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index 87a107c8ec..413867b18c 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -60,6 +60,7 @@ #include #include #include +#include #include #include #include @@ -78,12 +79,13 @@ #include #include +using namespace time_literals; + /** * Number of navigation modes that need on_active/on_inactive calls */ #define NAVIGATOR_MODE_ARRAY_SIZE 9 - class Navigator : public ModuleBase, public ModuleParams { public: @@ -332,11 +334,12 @@ private: int _local_pos_sub{-1}; /**< local position subscription */ int _vehicle_status_sub{-1}; /**< local position subscription */ + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _global_pos_sub{ORB_ID(vehicle_global_position)}; /**< global position subscription */ uORB::Subscription _gps_pos_sub{ORB_ID(vehicle_gps_position)}; /**< gps position subscription */ uORB::Subscription _home_pos_sub{ORB_ID(home_position)}; /**< home position subscription */ uORB::Subscription _land_detected_sub{ORB_ID(vehicle_land_detected)}; /**< vehicle land detected subscription */ - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; /**< param update subscription */ uORB::Subscription _pos_ctrl_landing_status_sub{ORB_ID(position_controller_landing_status)}; /**< position controller landing status subscription */ uORB::Subscription _traffic_sub{ORB_ID(transponder_report)}; /**< traffic subscription */ uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)}; /**< vehicle commands (onboard and offboard) */ diff --git a/src/modules/rc_update/rc_update.h b/src/modules/rc_update/rc_update.h index d0734ffb81..3ee7f290ed 100644 --- a/src/modules/rc_update/rc_update.h +++ b/src/modules/rc_update/rc_update.h @@ -60,6 +60,8 @@ #include #include +using namespace time_literals; + namespace RCUpdate { @@ -156,7 +158,8 @@ private: uORB::SubscriptionCallbackWorkItem _input_rc_sub{this, ORB_ID(input_rc)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _rc_parameter_map_sub{ORB_ID(rc_parameter_map)}; uORB::Publication _rc_channels_pub{ORB_ID(rc_channels)}; diff --git a/src/modules/rover_pos_control/RoverPositionControl.hpp b/src/modules/rover_pos_control/RoverPositionControl.hpp index 7efa2b471d..2795205bee 100644 --- a/src/modules/rover_pos_control/RoverPositionControl.hpp +++ b/src/modules/rover_pos_control/RoverPositionControl.hpp @@ -56,6 +56,7 @@ #include #include #include +#include #include #include #include @@ -69,11 +70,10 @@ #include #include #include -#include using matrix::Dcmf; -using uORB::SubscriptionData; +using namespace time_literals; class RoverPositionControl : public ModuleBase, public ModuleParams { @@ -111,7 +111,7 @@ private: int _vehicle_attitude_sub{-1}; int _sensor_combined_sub{-1}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; manual_control_setpoint_s _manual_control_setpoint{}; /**< r/c channel data */ position_setpoint_triplet_s _pos_sp_triplet{}; /**< triplet of mission items */ @@ -123,7 +123,7 @@ private: vehicle_attitude_s _vehicle_att{}; sensor_combined_s _sensor_combined{}; - SubscriptionData _vehicle_acceleration_sub{ORB_ID(vehicle_acceleration)}; + uORB::SubscriptionData _vehicle_acceleration_sub{ORB_ID(vehicle_acceleration)}; perf_counter_t _loop_perf; /**< loop performance counter */ diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 1cedca80c9..8cf3faa1f8 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -124,8 +124,9 @@ private: {this, ORB_ID(vehicle_imu), 3} }; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _diff_pres_sub{ORB_ID(differential_pressure)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _vcontrol_mode_sub{ORB_ID(vehicle_control_mode)}; uORB::Subscription _vehicle_air_data_sub{ORB_ID(vehicle_air_data)}; diff --git a/src/modules/sensors/vehicle_acceleration/VehicleAcceleration.cpp b/src/modules/sensors/vehicle_acceleration/VehicleAcceleration.cpp index 69aea8e753..d7a86c528b 100644 --- a/src/modules/sensors/vehicle_acceleration/VehicleAcceleration.cpp +++ b/src/modules/sensors/vehicle_acceleration/VehicleAcceleration.cpp @@ -38,7 +38,6 @@ #include using namespace matrix; -using namespace time_literals; namespace sensors { @@ -190,10 +189,10 @@ bool VehicleAcceleration::SensorSelectionUpdate(bool force) void VehicleAcceleration::ParametersUpdate(bool force) { // Check if parameters have changed - if (_params_sub.updated() || force) { + if (_parameter_update_sub.updated() || force) { // clear update parameter_update_s param_update; - _params_sub.copy(¶m_update); + _parameter_update_sub.copy(¶m_update); updateParams(); diff --git a/src/modules/sensors/vehicle_acceleration/VehicleAcceleration.hpp b/src/modules/sensors/vehicle_acceleration/VehicleAcceleration.hpp index f15e74a9d4..13d2d67865 100644 --- a/src/modules/sensors/vehicle_acceleration/VehicleAcceleration.hpp +++ b/src/modules/sensors/vehicle_acceleration/VehicleAcceleration.hpp @@ -51,6 +51,8 @@ #include #include +using namespace time_literals; + namespace sensors { @@ -79,7 +81,8 @@ private: uORB::Subscription _estimator_selector_status_sub{ORB_ID(estimator_selector_status)}; uORB::Subscription _estimator_sensor_bias_sub{ORB_ID(estimator_sensor_bias)}; - uORB::Subscription _params_sub{ORB_ID(parameter_update)}; + + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::SubscriptionCallbackWorkItem _sensor_selection_sub{this, ORB_ID(sensor_selection)}; uORB::SubscriptionCallbackWorkItem _sensor_sub{this, ORB_ID(sensor_accel)}; diff --git a/src/modules/sensors/vehicle_air_data/VehicleAirData.cpp b/src/modules/sensors/vehicle_air_data/VehicleAirData.cpp index 66e4d32ecf..438d9e6f08 100644 --- a/src/modules/sensors/vehicle_air_data/VehicleAirData.cpp +++ b/src/modules/sensors/vehicle_air_data/VehicleAirData.cpp @@ -40,7 +40,6 @@ namespace sensors { using namespace matrix; -using namespace time_literals; static constexpr uint32_t SENSOR_TIMEOUT{300_ms}; @@ -114,10 +113,10 @@ void VehicleAirData::SensorCorrectionsUpdate(bool force) void VehicleAirData::ParametersUpdate() { // Check if parameters have changed - if (_params_sub.updated()) { + if (_parameter_update_sub.updated()) { // clear update parameter_update_s param_update; - _params_sub.copy(¶m_update); + _parameter_update_sub.copy(¶m_update); updateParams(); } diff --git a/src/modules/sensors/vehicle_air_data/VehicleAirData.hpp b/src/modules/sensors/vehicle_air_data/VehicleAirData.hpp index 5570a6891f..3b6c10b2a0 100644 --- a/src/modules/sensors/vehicle_air_data/VehicleAirData.hpp +++ b/src/modules/sensors/vehicle_air_data/VehicleAirData.hpp @@ -51,6 +51,8 @@ #include #include +using namespace time_literals; + namespace sensors { class VehicleAirData : public ModuleParams, public px4::ScheduledWorkItem @@ -75,7 +77,8 @@ private: uORB::Publication _vehicle_air_data_pub{ORB_ID(vehicle_air_data)}; - uORB::Subscription _params_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _sensor_correction_sub{ORB_ID(sensor_correction)}; uORB::SubscriptionCallbackWorkItem _sensor_sub[MAX_SENSOR_COUNT] { diff --git a/src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.cpp b/src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.cpp index 133639186d..2dc0a836bc 100644 --- a/src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.cpp +++ b/src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.cpp @@ -38,7 +38,6 @@ #include using namespace matrix; -using namespace time_literals; namespace sensors { @@ -189,10 +188,10 @@ bool VehicleAngularVelocity::SensorSelectionUpdate(bool force) void VehicleAngularVelocity::ParametersUpdate(bool force) { // Check if parameters have changed - if (_params_sub.updated() || force) { + if (_parameter_update_sub.updated() || force) { // clear update parameter_update_s param_update; - _params_sub.copy(¶m_update); + _parameter_update_sub.copy(¶m_update); updateParams(); diff --git a/src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.hpp b/src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.hpp index 742f220ad6..82180faafb 100644 --- a/src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.hpp +++ b/src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.hpp @@ -53,6 +53,8 @@ #include #include +using namespace time_literals; + namespace sensors { @@ -82,7 +84,8 @@ private: uORB::Subscription _estimator_selector_status_sub{ORB_ID(estimator_selector_status)}; uORB::Subscription _estimator_sensor_bias_sub{ORB_ID(estimator_sensor_bias)}; - uORB::Subscription _params_sub{ORB_ID(parameter_update)}; + + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::SubscriptionCallbackWorkItem _sensor_selection_sub{this, ORB_ID(sensor_selection)}; uORB::SubscriptionCallbackWorkItem _sensor_sub{this, ORB_ID(sensor_gyro)}; diff --git a/src/modules/sensors/vehicle_gps_position/VehicleGPSPosition.cpp b/src/modules/sensors/vehicle_gps_position/VehicleGPSPosition.cpp index 78980c8069..375b2fbc45 100644 --- a/src/modules/sensors/vehicle_gps_position/VehicleGPSPosition.cpp +++ b/src/modules/sensors/vehicle_gps_position/VehicleGPSPosition.cpp @@ -77,10 +77,10 @@ void VehicleGPSPosition::Stop() void VehicleGPSPosition::ParametersUpdate(bool force) { // Check if parameters have changed - if (_params_sub.updated() || force) { + if (_parameter_update_sub.updated() || force) { // clear update parameter_update_s param_update; - _params_sub.copy(¶m_update); + _parameter_update_sub.copy(¶m_update); updateParams(); } diff --git a/src/modules/sensors/vehicle_gps_position/VehicleGPSPosition.hpp b/src/modules/sensors/vehicle_gps_position/VehicleGPSPosition.hpp index 7374799785..8c084f05d3 100644 --- a/src/modules/sensors/vehicle_gps_position/VehicleGPSPosition.hpp +++ b/src/modules/sensors/vehicle_gps_position/VehicleGPSPosition.hpp @@ -116,7 +116,7 @@ private: uORB::Publication _vehicle_gps_position_pub{ORB_ID(vehicle_gps_position)}; - uORB::Subscription _params_sub{ORB_ID(parameter_update)}; /**< parameter updates subscription */ + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::SubscriptionCallbackWorkItem _sensor_gps_sub[GPS_MAX_RECEIVERS] { /**< sensor data subscription */ {this, ORB_ID(sensor_gps), 0}, diff --git a/src/modules/sensors/vehicle_imu/VehicleIMU.cpp b/src/modules/sensors/vehicle_imu/VehicleIMU.cpp index 132f9df69e..034c4d551d 100644 --- a/src/modules/sensors/vehicle_imu/VehicleIMU.cpp +++ b/src/modules/sensors/vehicle_imu/VehicleIMU.cpp @@ -38,7 +38,6 @@ #include using namespace matrix; -using namespace time_literals; using math::constrain; @@ -111,10 +110,10 @@ void VehicleIMU::Stop() void VehicleIMU::ParametersUpdate(bool force) { // Check if parameters have changed - if (_params_sub.updated() || force) { + if (_parameter_update_sub.updated() || force) { // clear update parameter_update_s param_update; - _params_sub.copy(¶m_update); + _parameter_update_sub.copy(¶m_update); const auto imu_integ_rate_prev = _param_imu_integ_rate.get(); diff --git a/src/modules/sensors/vehicle_imu/VehicleIMU.hpp b/src/modules/sensors/vehicle_imu/VehicleIMU.hpp index 2ddf058c1f..15d091c3e7 100644 --- a/src/modules/sensors/vehicle_imu/VehicleIMU.hpp +++ b/src/modules/sensors/vehicle_imu/VehicleIMU.hpp @@ -53,6 +53,8 @@ #include #include +using namespace time_literals; + namespace sensors { @@ -87,7 +89,9 @@ private: uORB::PublicationMulti _vehicle_imu_pub{ORB_ID(vehicle_imu)}; uORB::PublicationMulti _vehicle_imu_status_pub{ORB_ID(vehicle_imu_status)}; - uORB::Subscription _params_sub{ORB_ID(parameter_update)}; + + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::SubscriptionCallbackWorkItem _sensor_accel_sub; uORB::SubscriptionCallbackWorkItem _sensor_gyro_sub; diff --git a/src/modules/sensors/vehicle_magnetometer/VehicleMagnetometer.cpp b/src/modules/sensors/vehicle_magnetometer/VehicleMagnetometer.cpp index f19d42a3e8..0331dc0399 100644 --- a/src/modules/sensors/vehicle_magnetometer/VehicleMagnetometer.cpp +++ b/src/modules/sensors/vehicle_magnetometer/VehicleMagnetometer.cpp @@ -40,7 +40,6 @@ namespace sensors { using namespace matrix; -using namespace time_literals; static constexpr uint32_t SENSOR_TIMEOUT{300_ms}; @@ -82,10 +81,10 @@ void VehicleMagnetometer::Stop() void VehicleMagnetometer::ParametersUpdate(bool force) { // Check if parameters have changed - if (_params_sub.updated() || force) { + if (_parameter_update_sub.updated() || force) { // clear update parameter_update_s param_update; - _params_sub.copy(¶m_update); + _parameter_update_sub.copy(¶m_update); updateParams(); diff --git a/src/modules/sensors/vehicle_magnetometer/VehicleMagnetometer.hpp b/src/modules/sensors/vehicle_magnetometer/VehicleMagnetometer.hpp index 8fdbf4000e..8b16f2402b 100644 --- a/src/modules/sensors/vehicle_magnetometer/VehicleMagnetometer.hpp +++ b/src/modules/sensors/vehicle_magnetometer/VehicleMagnetometer.hpp @@ -59,6 +59,8 @@ #include #include +using namespace time_literals; + namespace sensors { class VehicleMagnetometer : public ModuleParams, public px4::ScheduledWorkItem @@ -98,9 +100,10 @@ private: {ORB_ID(vehicle_magnetometer)}, }; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _actuator_controls_0_sub{ORB_ID(actuator_controls_0)}; uORB::Subscription _battery_status_sub{ORB_ID(battery_status), 0}; - uORB::Subscription _params_sub{ORB_ID(parameter_update)}; uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; // Used to check, save and use learned magnetometer biases diff --git a/src/modules/sih/sih.hpp b/src/modules/sih/sih.hpp index aab36a7c6a..9dbd191483 100644 --- a/src/modules/sih/sih.hpp +++ b/src/modules/sih/sih.hpp @@ -48,6 +48,7 @@ #include #include #include +#include #include #include #include @@ -55,6 +56,8 @@ #include // to publish groundtruth #include // to publish groundtruth +using namespace time_literals; + extern "C" __EXPORT int sih_main(int argc, char *argv[]); class Sih : public ModuleBase, public ModuleParams @@ -119,7 +122,7 @@ private: vehicle_global_position_s _gpos_gt{}; uORB::Publication _gpos_gt_pub{ORB_ID(vehicle_global_position_groundtruth)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::Subscription _actuator_out_sub{ORB_ID(actuator_outputs)}; // hard constants diff --git a/src/modules/simulator/battery_simulator/BatterySimulator.hpp b/src/modules/simulator/battery_simulator/BatterySimulator.hpp index 2ea3590c2e..8adf69be59 100644 --- a/src/modules/simulator/battery_simulator/BatterySimulator.hpp +++ b/src/modules/simulator/battery_simulator/BatterySimulator.hpp @@ -41,6 +41,7 @@ #include #include #include +#include #include #include #include @@ -72,7 +73,7 @@ private: uORB::Publication _battery_pub{ORB_ID(battery_status)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; Battery _battery; diff --git a/src/modules/simulator/simulator.h b/src/modules/simulator/simulator.h index f19b062097..b6a9aec15e 100644 --- a/src/modules/simulator/simulator.h +++ b/src/modules/simulator/simulator.h @@ -57,6 +57,7 @@ #include #include #include +#include #include #include #include @@ -200,7 +201,7 @@ private: uORB::PublicationMulti *_dist_pubs[RANGE_FINDER_MAX_SENSORS] {}; uint8_t _dist_sensor_ids[RANGE_FINDER_MAX_SENSORS] {}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; unsigned int _port{14560}; diff --git a/src/modules/temperature_compensation/TemperatureCompensationModule.cpp b/src/modules/temperature_compensation/TemperatureCompensationModule.cpp index 9c6b2e1cf4..c337a37a81 100644 --- a/src/modules/temperature_compensation/TemperatureCompensationModule.cpp +++ b/src/modules/temperature_compensation/TemperatureCompensationModule.cpp @@ -41,7 +41,6 @@ #include using namespace temperature_compensation; -using namespace time_literals; TemperatureCompensationModule::TemperatureCompensationModule() : ModuleParams(nullptr), @@ -233,10 +232,10 @@ void TemperatureCompensationModule::Run() } // Check if any parameter has changed - if (_params_sub.updated()) { + if (_parameter_update_sub.updated()) { // Read from param to clear updated flag parameter_update_s update; - _params_sub.copy(&update); + _parameter_update_sub.copy(&update); parameters_update(); } diff --git a/src/modules/temperature_compensation/TemperatureCompensationModule.h b/src/modules/temperature_compensation/TemperatureCompensationModule.h index 282befe60c..24e9ea5f49 100644 --- a/src/modules/temperature_compensation/TemperatureCompensationModule.h +++ b/src/modules/temperature_compensation/TemperatureCompensationModule.h @@ -48,6 +48,7 @@ #include #include #include +#include #include #include #include @@ -58,6 +59,8 @@ #include "TemperatureCompensation.h" +using namespace time_literals; + namespace temperature_compensation { @@ -123,7 +126,8 @@ private: {ORB_ID(sensor_baro), 3}, }; - uORB::Subscription _params_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)}; perf_counter_t _loop_perf; /**< loop performance counter */ diff --git a/src/modules/uuv_att_control/uuv_att_control.hpp b/src/modules/uuv_att_control/uuv_att_control.hpp index d18bd8e78f..bdb642a860 100644 --- a/src/modules/uuv_att_control/uuv_att_control.hpp +++ b/src/modules/uuv_att_control/uuv_att_control.hpp @@ -43,8 +43,6 @@ * @author Tim Hansen */ - - #include #include @@ -81,6 +79,8 @@ using matrix::Dcmf; using uORB::SubscriptionData; +using namespace time_literals; + class UUVAttitudeControl: public ModuleBase, public ModuleParams, public px4::WorkItem { public: @@ -100,7 +100,7 @@ public: private: uORB::Publication _actuator_controls_pub{ORB_ID(actuator_controls_0)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::Subscription _vehicle_attitude_setpoint_sub{ORB_ID(vehicle_attitude_setpoint)}; /**< vehicle attitude setpoint */ uORB::Subscription _vehicle_rates_setpoint_sub{ORB_ID(vehicle_rates_setpoint)}; /**< vehicle bodyrates setpoint subscriber */ diff --git a/src/modules/vmount/vmount.cpp b/src/modules/vmount/vmount.cpp index 622c26e882..d853d3bd0c 100644 --- a/src/modules/vmount/vmount.cpp +++ b/src/modules/vmount/vmount.cpp @@ -63,11 +63,13 @@ #include "output_mavlink.h" #include +#include #include #include #include +using namespace time_literals; using namespace vmount; /* thread state */ @@ -208,7 +210,7 @@ static int vmount_thread_main(int argc, char *argv[]) return -1; } - uORB::Subscription parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval parameter_update_sub{ORB_ID(parameter_update), 1_s}; thread_running = true; ControlData *control_data = nullptr; g_thread_data = &thread_data; diff --git a/src/modules/vtol_att_control/vtol_att_control_main.h b/src/modules/vtol_att_control/vtol_att_control_main.h index adc873b34c..3c6b35f6c8 100644 --- a/src/modules/vtol_att_control/vtol_att_control_main.h +++ b/src/modules/vtol_att_control/vtol_att_control_main.h @@ -84,6 +84,8 @@ #include "tailsitter.h" #include "tiltrotor.h" +using namespace time_literals; + extern "C" __EXPORT int vtol_att_control_main(int argc, char *argv[]); class VtolAttitudeControl : public ModuleBase, public px4::WorkItem @@ -133,6 +135,8 @@ private: uORB::SubscriptionCallbackWorkItem _actuator_inputs_fw{this, ORB_ID(actuator_controls_virtual_fw)}; uORB::SubscriptionCallbackWorkItem _actuator_inputs_mc{this, ORB_ID(actuator_controls_virtual_mc)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uORB::Subscription _airspeed_validated_sub{ORB_ID(airspeed_validated)}; // airspeed subscription uORB::Subscription _fw_virtual_att_sp_sub{ORB_ID(fw_virtual_attitude_setpoint)}; uORB::Subscription _land_detected_sub{ORB_ID(vehicle_land_detected)}; @@ -140,7 +144,6 @@ private: uORB::Subscription _local_pos_sub{ORB_ID(vehicle_local_position)}; // sensor subscription uORB::Subscription _manual_control_switches_sub{ORB_ID(manual_control_switches)}; //manual control setpoint subscription uORB::Subscription _mc_virtual_att_sp_sub{ORB_ID(mc_virtual_attitude_setpoint)}; - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _pos_sp_triplet_sub{ORB_ID(position_setpoint_triplet)}; // local position setpoint subscription uORB::Subscription _tecs_status_sub{ORB_ID(tecs_status)}; uORB::Subscription _v_att_sub{ORB_ID(vehicle_attitude)}; //vehicle attitude subscription diff --git a/src/templates/template_module/template_module.h b/src/templates/template_module/template_module.h index 909249c7bf..624d10cf02 100644 --- a/src/templates/template_module/template_module.h +++ b/src/templates/template_module/template_module.h @@ -82,7 +82,7 @@ private: ) // Subscriptions - uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; };