Browse Source

WorkItem modules: Run() shouldn't be public

sbg
Daniel Agar 5 years ago
parent
commit
21a8d7db7f
  1. 5
      platforms/common/px4_work_queue/test/wqueue_scheduled_test.h
  2. 5
      platforms/common/px4_work_queue/test/wqueue_test.h
  3. 3
      src/drivers/batt_smbus/batt_smbus.h
  4. 4
      src/drivers/distance_sensor/ll40ls/LidarLitePWM.h
  5. 5
      src/drivers/dshot/dshot.cpp
  6. 4
      src/drivers/imu/icm20948/icm20948.h
  7. 4
      src/drivers/imu/mpu9250/mpu9250.h
  8. 5
      src/drivers/pwm_out_sim/PWMSim.hpp
  9. 6
      src/drivers/rc_input/RCInput.hpp
  10. 5
      src/drivers/safety_button/SafetyButton.hpp
  11. 4
      src/modules/airspeed_selector/airspeed_selector_main.cpp
  12. 4
      src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp
  13. 3
      src/modules/battery_status/battery_status.cpp
  14. 4
      src/modules/camera_feedback/CameraFeedback.hpp
  15. 4
      src/modules/ekf2/ekf2_main.cpp
  16. 3
      src/modules/fw_att_control/FixedwingAttitudeControl.hpp
  17. 4
      src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp
  18. 3
      src/modules/mc_att_control/mc_att_control.hpp
  19. 4
      src/modules/mc_pos_control/mc_pos_control_main.cpp
  20. 3
      src/modules/mc_rate_control/MulticopterRateControl.hpp
  21. 3
      src/modules/rc_update/rc_update.h
  22. 4
      src/modules/temperature_compensation/TemperatureCompensationModule.h
  23. 6
      src/modules/vtol_att_control/vtol_att_control_main.h

5
platforms/common/px4_work_queue/test/wqueue_scheduled_test.h

@ -47,10 +47,11 @@ public: @@ -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};
};

5
platforms/common/px4_work_queue/test/wqueue_test.h

@ -47,10 +47,11 @@ public: @@ -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};
};

3
src/drivers/batt_smbus/batt_smbus.h

@ -242,11 +242,10 @@ public: @@ -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")};

4
src/drivers/distance_sensor/ll40ls/LidarLitePWM.h

@ -65,8 +65,6 @@ public: @@ -65,8 +65,6 @@ public:
void start() override;
void stop() override;
void Run() override;
protected:
int collect() override;
@ -74,6 +72,8 @@ protected: @@ -74,6 +72,8 @@ protected:
private:
void Run() override;
uORB::Subscription _sub_pwm_input{ORB_ID(pwm_input)};
pwm_input_s _pwm{};

5
src/drivers/dshot/dshot.cpp

@ -127,8 +127,6 @@ public: @@ -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: @@ -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 {

4
src/drivers/imu/icm20948/icm20948.h

@ -369,10 +369,10 @@ protected: @@ -369,10 +369,10 @@ protected:
friend class ICM20948_mag;
void Run() override;
private:
void Run() override;
PX4Accelerometer _px4_accel;
PX4Gyroscope _px4_gyro;

4
src/drivers/imu/mpu9250/mpu9250.h

@ -254,10 +254,10 @@ protected: @@ -254,10 +254,10 @@ protected:
friend class MPU9250_mag;
void Run() override;
private:
void Run() override;
PX4Accelerometer _px4_accel;
PX4Gyroscope _px4_gyro;

5
src/drivers/pwm_out_sim/PWMSim.hpp

@ -61,14 +61,15 @@ public: @@ -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;

6
src/drivers/rc_input/RCInput.hpp

@ -77,15 +77,15 @@ public: @@ -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,

5
src/drivers/safety_button/SafetyButton.hpp

@ -55,7 +55,7 @@ class SafetyButton : public ModuleBase<SafetyButton>, public px4::ScheduledWorkI @@ -55,7 +55,7 @@ class SafetyButton : public ModuleBase<SafetyButton>, public px4::ScheduledWorkI
{
public:
SafetyButton();
virtual ~SafetyButton();
~SafetyButton() override;
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
@ -69,11 +69,10 @@ public: @@ -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();

4
src/modules/airspeed_selector/airspeed_selector_main.cpp

@ -87,10 +87,10 @@ public: @@ -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,

4
src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp

@ -85,12 +85,12 @@ public: @@ -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();

3
src/modules/battery_status/battery_status.cpp

@ -94,10 +94,11 @@ public: @@ -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 */

4
src/modules/camera_feedback/CameraFeedback.hpp

@ -71,12 +71,12 @@ public: @@ -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)};

4
src/modules/ekf2/ekf2_main.cpp

@ -107,13 +107,13 @@ public: @@ -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);

3
src/modules/fw_att_control/FixedwingAttitudeControl.hpp

@ -88,11 +88,10 @@ public: @@ -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 */

4
src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp

@ -141,11 +141,11 @@ public: @@ -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)};

3
src/modules/mc_att_control/mc_att_control.hpp

@ -78,11 +78,10 @@ public: @@ -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

4
src/modules/mc_pos_control/mc_pos_control_main.cpp

@ -95,14 +95,14 @@ public: @@ -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_s> _vehicle_attitude_setpoint_pub;

3
src/modules/mc_rate_control/MulticopterRateControl.hpp

@ -75,11 +75,10 @@ public: @@ -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

3
src/modules/rc_update/rc_update.h

@ -83,11 +83,12 @@ public: @@ -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
*/

4
src/modules/temperature_compensation/TemperatureCompensationModule.h

@ -80,8 +80,6 @@ public: @@ -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: @@ -92,6 +90,8 @@ public:
private:
void Run() override;
void accelPoll();
void gyroPoll();
void baroPoll();

6
src/modules/vtol_att_control/vtol_att_control_main.h

@ -91,7 +91,7 @@ class VtolAttitudeControl : public ModuleBase<VtolAttitudeControl>, public px4:: @@ -91,7 +91,7 @@ class VtolAttitudeControl : public ModuleBase<VtolAttitudeControl>, public px4::
public:
VtolAttitudeControl();
~VtolAttitudeControl();
~VtolAttitudeControl() override;
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
@ -102,8 +102,6 @@ public: @@ -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: @@ -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)};

Loading…
Cancel
Save