diff --git a/platforms/common/px4_work_queue/test/wqueue_scheduled_test.h b/platforms/common/px4_work_queue/test/wqueue_scheduled_test.h index c793ee8d9d..73830441f4 100644 --- a/platforms/common/px4_work_queue/test/wqueue_scheduled_test.h +++ b/platforms/common/px4_work_queue/test/wqueue_scheduled_test.h @@ -47,10 +47,11 @@ public: int main(); - void Run() override; - static px4::AppState appState; /* track requests to terminate app */ private: + + void Run() override; + int _iter{0}; }; diff --git a/platforms/common/px4_work_queue/test/wqueue_test.h b/platforms/common/px4_work_queue/test/wqueue_test.h index ea5b3f250f..386dcdbe0d 100644 --- a/platforms/common/px4_work_queue/test/wqueue_test.h +++ b/platforms/common/px4_work_queue/test/wqueue_test.h @@ -47,10 +47,11 @@ public: int main(); - void Run() override; - static px4::AppState appState; /* track requests to terminate app */ private: + + void Run() override; + int _iter{0}; }; diff --git a/src/drivers/batt_smbus/batt_smbus.h b/src/drivers/batt_smbus/batt_smbus.h index cda4f0a3a2..89b8978d30 100644 --- a/src/drivers/batt_smbus/batt_smbus.h +++ b/src/drivers/batt_smbus/batt_smbus.h @@ -242,11 +242,10 @@ public: void resume(); -protected: +private: void Run() override; -private: SMBus *_interface; perf_counter_t _cycle{perf_alloc(PC_ELAPSED, "batt_smbus_cycle")}; diff --git a/src/drivers/distance_sensor/ll40ls/LidarLitePWM.h b/src/drivers/distance_sensor/ll40ls/LidarLitePWM.h index 511ea3c4a1..2e4dfc4b67 100644 --- a/src/drivers/distance_sensor/ll40ls/LidarLitePWM.h +++ b/src/drivers/distance_sensor/ll40ls/LidarLitePWM.h @@ -65,8 +65,6 @@ public: void start() override; void stop() override; - void Run() override; - protected: int collect() override; @@ -74,6 +72,8 @@ protected: private: + void Run() override; + uORB::Subscription _sub_pwm_input{ORB_ID(pwm_input)}; pwm_input_s _pwm{}; diff --git a/src/drivers/dshot/dshot.cpp b/src/drivers/dshot/dshot.cpp index a1d7fcd3be..cc6654a6f7 100644 --- a/src/drivers/dshot/dshot.cpp +++ b/src/drivers/dshot/dshot.cpp @@ -127,8 +127,6 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - void Run() override; - /** @see ModuleBase::print_status() */ int print_status() override; @@ -165,6 +163,9 @@ public: bool telemetryEnabled() const { return _telemetry != nullptr; } private: + + void Run() override; + static constexpr uint16_t DISARMED_VALUE = 0; enum class DShotConfig { diff --git a/src/drivers/imu/icm20948/icm20948.h b/src/drivers/imu/icm20948/icm20948.h index 682d48283b..afbe3d2eef 100644 --- a/src/drivers/imu/icm20948/icm20948.h +++ b/src/drivers/imu/icm20948/icm20948.h @@ -369,10 +369,10 @@ protected: friend class ICM20948_mag; - void Run() override; - private: + void Run() override; + PX4Accelerometer _px4_accel; PX4Gyroscope _px4_gyro; diff --git a/src/drivers/imu/mpu9250/mpu9250.h b/src/drivers/imu/mpu9250/mpu9250.h index 84a20157e5..30508bcbba 100644 --- a/src/drivers/imu/mpu9250/mpu9250.h +++ b/src/drivers/imu/mpu9250/mpu9250.h @@ -254,10 +254,10 @@ protected: friend class MPU9250_mag; - void Run() override; - private: + void Run() override; + PX4Accelerometer _px4_accel; PX4Gyroscope _px4_gyro; diff --git a/src/drivers/pwm_out_sim/PWMSim.hpp b/src/drivers/pwm_out_sim/PWMSim.hpp index 7282484237..c61262f79a 100644 --- a/src/drivers/pwm_out_sim/PWMSim.hpp +++ b/src/drivers/pwm_out_sim/PWMSim.hpp @@ -61,14 +61,15 @@ public: /** @see ModuleBase::print_status() */ int print_status() override; - void Run() override; - int ioctl(device::file_t *filp, int cmd, unsigned long arg) override; bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs, unsigned num_control_groups_updated) override; private: + + void Run() override; + static constexpr uint16_t PWM_SIM_DISARMED_MAGIC = 900; static constexpr uint16_t PWM_SIM_FAILSAFE_MAGIC = 600; static constexpr uint16_t PWM_SIM_PWM_MIN_MAGIC = 1000; diff --git a/src/drivers/rc_input/RCInput.hpp b/src/drivers/rc_input/RCInput.hpp index 1b42dc36e5..966e7f3d28 100644 --- a/src/drivers/rc_input/RCInput.hpp +++ b/src/drivers/rc_input/RCInput.hpp @@ -77,15 +77,15 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - /** @see ModuleBase::run() */ - void Run() override; - /** @see ModuleBase::print_status() */ int print_status() override; int init(); private: + + void Run() override; + enum RC_SCAN { RC_SCAN_PPM = 0, RC_SCAN_SBUS, diff --git a/src/drivers/safety_button/SafetyButton.hpp b/src/drivers/safety_button/SafetyButton.hpp index 2619bdaf52..9eaf6c4a1b 100644 --- a/src/drivers/safety_button/SafetyButton.hpp +++ b/src/drivers/safety_button/SafetyButton.hpp @@ -55,7 +55,7 @@ class SafetyButton : public ModuleBase, public px4::ScheduledWorkI { public: SafetyButton(); - virtual ~SafetyButton(); + ~SafetyButton() override; /** @see ModuleBase */ static int task_spawn(int argc, char *argv[]); @@ -69,11 +69,10 @@ public: /** @see ModuleBase::print_status() */ int print_status() override; - void Run() override; - int Start(); private: + void Run() override; void CheckButton(); void FlashButton(); diff --git a/src/modules/airspeed_selector/airspeed_selector_main.cpp b/src/modules/airspeed_selector/airspeed_selector_main.cpp index f466cc1197..e6a3822498 100644 --- a/src/modules/airspeed_selector/airspeed_selector_main.cpp +++ b/src/modules/airspeed_selector/airspeed_selector_main.cpp @@ -87,10 +87,10 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - /* run the main loop */ +private: + void Run() override; -private: static constexpr int MAX_NUM_AIRSPEED_SENSORS = 3; /**< Support max 3 airspeed sensors */ enum airspeed_index { DISABLED_INDEX = -1, 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 e113bb4962..47db41d7f6 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp @@ -85,12 +85,12 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - void Run() override; - bool init(); private: + void Run() override; + void update_parameters(bool force = false); bool init_attq(); diff --git a/src/modules/battery_status/battery_status.cpp b/src/modules/battery_status/battery_status.cpp index c45f96cac5..4960cc79f7 100644 --- a/src/modules/battery_status/battery_status.cpp +++ b/src/modules/battery_status/battery_status.cpp @@ -94,10 +94,11 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - void Run() override; bool init(); private: + void Run() override; + int _adc_fd{-1}; /**< ADC file handle */ uORB::Subscription _actuator_ctrl_0_sub{ORB_ID(actuator_controls_0)}; /**< attitude controls sub */ diff --git a/src/modules/camera_feedback/CameraFeedback.hpp b/src/modules/camera_feedback/CameraFeedback.hpp index a08642c31d..73204ecd4f 100644 --- a/src/modules/camera_feedback/CameraFeedback.hpp +++ b/src/modules/camera_feedback/CameraFeedback.hpp @@ -71,12 +71,12 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - void Run() override; - bool init(); private: + void Run() override; + uORB::SubscriptionCallbackWorkItem _trigger_sub{this, ORB_ID(camera_trigger)}; uORB::Subscription _gpos_sub{ORB_ID(vehicle_global_position)}; diff --git a/src/modules/ekf2/ekf2_main.cpp b/src/modules/ekf2/ekf2_main.cpp index 79d64986f3..4ea439792b 100644 --- a/src/modules/ekf2/ekf2_main.cpp +++ b/src/modules/ekf2/ekf2_main.cpp @@ -107,13 +107,13 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - void Run() override; - bool init(); int print_status() override; private: + void Run() override; + int getRangeSubIndex(); ///< get subscription index of first downward-facing range sensor void fillGpsMsgWithVehicleGpsPosData(gps_message &msg, const vehicle_gps_position_s &data); diff --git a/src/modules/fw_att_control/FixedwingAttitudeControl.hpp b/src/modules/fw_att_control/FixedwingAttitudeControl.hpp index 3ce5ab1ca7..5c48d50735 100644 --- a/src/modules/fw_att_control/FixedwingAttitudeControl.hpp +++ b/src/modules/fw_att_control/FixedwingAttitudeControl.hpp @@ -88,11 +88,10 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - void Run() override; - bool init(); private: + void Run() override; uORB::SubscriptionCallbackWorkItem _att_sub{this, ORB_ID(vehicle_attitude)}; /**< vehicle attitude */ diff --git a/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp b/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp index 8505e5647f..454ed721c4 100644 --- a/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp +++ b/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp @@ -141,11 +141,11 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - void Run() override; - bool init(); private: + void Run() override; + orb_advert_t _mavlink_log_pub{nullptr}; uORB::SubscriptionCallbackWorkItem _global_pos_sub{this, ORB_ID(vehicle_global_position)}; diff --git a/src/modules/mc_att_control/mc_att_control.hpp b/src/modules/mc_att_control/mc_att_control.hpp index 701cfb356e..37cc736a54 100644 --- a/src/modules/mc_att_control/mc_att_control.hpp +++ b/src/modules/mc_att_control/mc_att_control.hpp @@ -78,11 +78,10 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - void Run() override; - bool init(); private: + void Run() override; /** * initialize some vectors/matrices from parameters diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 693a00932e..4747130569 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -95,14 +95,14 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - void Run() override; - bool init(); /** @see ModuleBase::print_status() */ int print_status() override; private: + void Run() override; + Takeoff _takeoff; /**< state machine and ramp to bring the vehicle off the ground without jumps */ uORB::Publication _vehicle_attitude_setpoint_pub; diff --git a/src/modules/mc_rate_control/MulticopterRateControl.hpp b/src/modules/mc_rate_control/MulticopterRateControl.hpp index 09124ea8a4..5ab978ef97 100644 --- a/src/modules/mc_rate_control/MulticopterRateControl.hpp +++ b/src/modules/mc_rate_control/MulticopterRateControl.hpp @@ -75,11 +75,10 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - void Run() override; - bool init(); private: + void Run() override; /** * initialize some vectors/matrices from parameters diff --git a/src/modules/rc_update/rc_update.h b/src/modules/rc_update/rc_update.h index 73106e570f..26b8197ce8 100644 --- a/src/modules/rc_update/rc_update.h +++ b/src/modules/rc_update/rc_update.h @@ -83,11 +83,12 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - void Run() override; bool init(); private: + void Run() override; + /** * Check for changes in rc_parameter_map */ diff --git a/src/modules/temperature_compensation/TemperatureCompensationModule.h b/src/modules/temperature_compensation/TemperatureCompensationModule.h index b8ee47f61a..67fa8cb453 100644 --- a/src/modules/temperature_compensation/TemperatureCompensationModule.h +++ b/src/modules/temperature_compensation/TemperatureCompensationModule.h @@ -80,8 +80,6 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - void Run() override; - /** @see ModuleBase::print_status() */ int print_status() override; @@ -92,6 +90,8 @@ public: private: + void Run() override; + void accelPoll(); void gyroPoll(); void baroPoll(); 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 3c6b889fe7..a88b4a7321 100644 --- a/src/modules/vtol_att_control/vtol_att_control_main.h +++ b/src/modules/vtol_att_control/vtol_att_control_main.h @@ -91,7 +91,7 @@ class VtolAttitudeControl : public ModuleBase, public px4:: public: VtolAttitudeControl(); - ~VtolAttitudeControl(); + ~VtolAttitudeControl() override; /** @see ModuleBase */ static int task_spawn(int argc, char *argv[]); @@ -102,8 +102,6 @@ public: /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); - void Run() override; - bool init(); bool is_fixed_wing_requested(); @@ -130,6 +128,8 @@ public: private: + void Run() override; + uORB::SubscriptionCallbackWorkItem _actuator_inputs_fw{this, ORB_ID(actuator_controls_virtual_fw)}; uORB::SubscriptionCallbackWorkItem _actuator_inputs_mc{this, ORB_ID(actuator_controls_virtual_mc)};