mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 01:12:11 +00:00
WorkItem modules: Run() shouldn't be public
This commit is contained in:
@@ -47,10 +47,11 @@ public:
|
|||||||
|
|
||||||
int main();
|
int main();
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
static px4::AppState appState; /* track requests to terminate app */
|
static px4::AppState appState; /* track requests to terminate app */
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
int _iter{0};
|
int _iter{0};
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -47,10 +47,11 @@ public:
|
|||||||
|
|
||||||
int main();
|
int main();
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
static px4::AppState appState; /* track requests to terminate app */
|
static px4::AppState appState; /* track requests to terminate app */
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
int _iter{0};
|
int _iter{0};
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -242,11 +242,10 @@ public:
|
|||||||
|
|
||||||
void resume();
|
void resume();
|
||||||
|
|
||||||
protected:
|
private:
|
||||||
|
|
||||||
void Run() override;
|
void Run() override;
|
||||||
|
|
||||||
private:
|
|
||||||
SMBus *_interface;
|
SMBus *_interface;
|
||||||
|
|
||||||
perf_counter_t _cycle{perf_alloc(PC_ELAPSED, "batt_smbus_cycle")};
|
perf_counter_t _cycle{perf_alloc(PC_ELAPSED, "batt_smbus_cycle")};
|
||||||
|
|||||||
@@ -65,8 +65,6 @@ public:
|
|||||||
void start() override;
|
void start() override;
|
||||||
void stop() override;
|
void stop() override;
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
int collect() override;
|
int collect() override;
|
||||||
@@ -74,6 +72,8 @@ protected:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
uORB::Subscription _sub_pwm_input{ORB_ID(pwm_input)};
|
uORB::Subscription _sub_pwm_input{ORB_ID(pwm_input)};
|
||||||
|
|
||||||
pwm_input_s _pwm{};
|
pwm_input_s _pwm{};
|
||||||
|
|||||||
@@ -127,8 +127,6 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
/** @see ModuleBase::print_status() */
|
/** @see ModuleBase::print_status() */
|
||||||
int print_status() override;
|
int print_status() override;
|
||||||
|
|
||||||
@@ -165,6 +163,9 @@ public:
|
|||||||
bool telemetryEnabled() const { return _telemetry != nullptr; }
|
bool telemetryEnabled() const { return _telemetry != nullptr; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
static constexpr uint16_t DISARMED_VALUE = 0;
|
static constexpr uint16_t DISARMED_VALUE = 0;
|
||||||
|
|
||||||
enum class DShotConfig {
|
enum class DShotConfig {
|
||||||
|
|||||||
@@ -369,10 +369,10 @@ protected:
|
|||||||
|
|
||||||
friend class ICM20948_mag;
|
friend class ICM20948_mag;
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
PX4Accelerometer _px4_accel;
|
PX4Accelerometer _px4_accel;
|
||||||
PX4Gyroscope _px4_gyro;
|
PX4Gyroscope _px4_gyro;
|
||||||
|
|
||||||
|
|||||||
@@ -254,10 +254,10 @@ protected:
|
|||||||
|
|
||||||
friend class MPU9250_mag;
|
friend class MPU9250_mag;
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
PX4Accelerometer _px4_accel;
|
PX4Accelerometer _px4_accel;
|
||||||
PX4Gyroscope _px4_gyro;
|
PX4Gyroscope _px4_gyro;
|
||||||
|
|
||||||
|
|||||||
@@ -61,14 +61,15 @@ public:
|
|||||||
/** @see ModuleBase::print_status() */
|
/** @see ModuleBase::print_status() */
|
||||||
int print_status() override;
|
int print_status() override;
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
int ioctl(device::file_t *filp, int cmd, unsigned long arg) override;
|
int ioctl(device::file_t *filp, int cmd, unsigned long arg) override;
|
||||||
|
|
||||||
bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
|
bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
|
||||||
unsigned num_outputs, unsigned num_control_groups_updated) override;
|
unsigned num_outputs, unsigned num_control_groups_updated) override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
static constexpr uint16_t PWM_SIM_DISARMED_MAGIC = 900;
|
static constexpr uint16_t PWM_SIM_DISARMED_MAGIC = 900;
|
||||||
static constexpr uint16_t PWM_SIM_FAILSAFE_MAGIC = 600;
|
static constexpr uint16_t PWM_SIM_FAILSAFE_MAGIC = 600;
|
||||||
static constexpr uint16_t PWM_SIM_PWM_MIN_MAGIC = 1000;
|
static constexpr uint16_t PWM_SIM_PWM_MIN_MAGIC = 1000;
|
||||||
|
|||||||
@@ -77,15 +77,15 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
/** @see ModuleBase::run() */
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
/** @see ModuleBase::print_status() */
|
/** @see ModuleBase::print_status() */
|
||||||
int print_status() override;
|
int print_status() override;
|
||||||
|
|
||||||
int init();
|
int init();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
enum RC_SCAN {
|
enum RC_SCAN {
|
||||||
RC_SCAN_PPM = 0,
|
RC_SCAN_PPM = 0,
|
||||||
RC_SCAN_SBUS,
|
RC_SCAN_SBUS,
|
||||||
|
|||||||
@@ -55,7 +55,7 @@ class SafetyButton : public ModuleBase<SafetyButton>, public px4::ScheduledWorkI
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
SafetyButton();
|
SafetyButton();
|
||||||
virtual ~SafetyButton();
|
~SafetyButton() override;
|
||||||
|
|
||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int task_spawn(int argc, char *argv[]);
|
static int task_spawn(int argc, char *argv[]);
|
||||||
@@ -69,11 +69,10 @@ public:
|
|||||||
/** @see ModuleBase::print_status() */
|
/** @see ModuleBase::print_status() */
|
||||||
int print_status() override;
|
int print_status() override;
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
int Start();
|
int Start();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
void CheckButton();
|
void CheckButton();
|
||||||
void FlashButton();
|
void FlashButton();
|
||||||
|
|||||||
@@ -87,10 +87,10 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
/* run the main loop */
|
private:
|
||||||
|
|
||||||
void Run() override;
|
void Run() override;
|
||||||
|
|
||||||
private:
|
|
||||||
static constexpr int MAX_NUM_AIRSPEED_SENSORS = 3; /**< Support max 3 airspeed sensors */
|
static constexpr int MAX_NUM_AIRSPEED_SENSORS = 3; /**< Support max 3 airspeed sensors */
|
||||||
enum airspeed_index {
|
enum airspeed_index {
|
||||||
DISABLED_INDEX = -1,
|
DISABLED_INDEX = -1,
|
||||||
|
|||||||
@@ -85,12 +85,12 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
bool init();
|
bool init();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
void update_parameters(bool force = false);
|
void update_parameters(bool force = false);
|
||||||
|
|
||||||
bool init_attq();
|
bool init_attq();
|
||||||
|
|||||||
@@ -94,10 +94,11 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
bool init();
|
bool init();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
int _adc_fd{-1}; /**< ADC file handle */
|
int _adc_fd{-1}; /**< ADC file handle */
|
||||||
|
|
||||||
uORB::Subscription _actuator_ctrl_0_sub{ORB_ID(actuator_controls_0)}; /**< attitude controls sub */
|
uORB::Subscription _actuator_ctrl_0_sub{ORB_ID(actuator_controls_0)}; /**< attitude controls sub */
|
||||||
|
|||||||
@@ -71,12 +71,12 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
bool init();
|
bool init();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
uORB::SubscriptionCallbackWorkItem _trigger_sub{this, ORB_ID(camera_trigger)};
|
uORB::SubscriptionCallbackWorkItem _trigger_sub{this, ORB_ID(camera_trigger)};
|
||||||
|
|
||||||
uORB::Subscription _gpos_sub{ORB_ID(vehicle_global_position)};
|
uORB::Subscription _gpos_sub{ORB_ID(vehicle_global_position)};
|
||||||
|
|||||||
@@ -107,13 +107,13 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
bool init();
|
bool init();
|
||||||
|
|
||||||
int print_status() override;
|
int print_status() override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
int getRangeSubIndex(); ///< get subscription index of first downward-facing range sensor
|
int getRangeSubIndex(); ///< get subscription index of first downward-facing range sensor
|
||||||
void fillGpsMsgWithVehicleGpsPosData(gps_message &msg, const vehicle_gps_position_s &data);
|
void fillGpsMsgWithVehicleGpsPosData(gps_message &msg, const vehicle_gps_position_s &data);
|
||||||
|
|
||||||
|
|||||||
@@ -88,11 +88,10 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
bool init();
|
bool init();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
uORB::SubscriptionCallbackWorkItem _att_sub{this, ORB_ID(vehicle_attitude)}; /**< vehicle attitude */
|
uORB::SubscriptionCallbackWorkItem _att_sub{this, ORB_ID(vehicle_attitude)}; /**< vehicle attitude */
|
||||||
|
|
||||||
|
|||||||
@@ -141,11 +141,11 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
bool init();
|
bool init();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
orb_advert_t _mavlink_log_pub{nullptr};
|
orb_advert_t _mavlink_log_pub{nullptr};
|
||||||
|
|
||||||
uORB::SubscriptionCallbackWorkItem _global_pos_sub{this, ORB_ID(vehicle_global_position)};
|
uORB::SubscriptionCallbackWorkItem _global_pos_sub{this, ORB_ID(vehicle_global_position)};
|
||||||
|
|||||||
@@ -78,11 +78,10 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
bool init();
|
bool init();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* initialize some vectors/matrices from parameters
|
* initialize some vectors/matrices from parameters
|
||||||
|
|||||||
@@ -95,14 +95,14 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
bool init();
|
bool init();
|
||||||
|
|
||||||
/** @see ModuleBase::print_status() */
|
/** @see ModuleBase::print_status() */
|
||||||
int print_status() override;
|
int print_status() override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
Takeoff _takeoff; /**< state machine and ramp to bring the vehicle off the ground without jumps */
|
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;
|
uORB::Publication<vehicle_attitude_setpoint_s> _vehicle_attitude_setpoint_pub;
|
||||||
|
|||||||
@@ -75,11 +75,10 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
bool init();
|
bool init();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* initialize some vectors/matrices from parameters
|
* initialize some vectors/matrices from parameters
|
||||||
|
|||||||
@@ -83,11 +83,12 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
bool init();
|
bool init();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Check for changes in rc_parameter_map
|
* Check for changes in rc_parameter_map
|
||||||
*/
|
*/
|
||||||
|
|||||||
@@ -80,8 +80,6 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
/** @see ModuleBase::print_status() */
|
/** @see ModuleBase::print_status() */
|
||||||
int print_status() override;
|
int print_status() override;
|
||||||
|
|
||||||
@@ -92,6 +90,8 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
void accelPoll();
|
void accelPoll();
|
||||||
void gyroPoll();
|
void gyroPoll();
|
||||||
void baroPoll();
|
void baroPoll();
|
||||||
|
|||||||
@@ -91,7 +91,7 @@ class VtolAttitudeControl : public ModuleBase<VtolAttitudeControl>, public px4::
|
|||||||
public:
|
public:
|
||||||
|
|
||||||
VtolAttitudeControl();
|
VtolAttitudeControl();
|
||||||
~VtolAttitudeControl();
|
~VtolAttitudeControl() override;
|
||||||
|
|
||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int task_spawn(int argc, char *argv[]);
|
static int task_spawn(int argc, char *argv[]);
|
||||||
@@ -102,8 +102,6 @@ public:
|
|||||||
/** @see ModuleBase */
|
/** @see ModuleBase */
|
||||||
static int print_usage(const char *reason = nullptr);
|
static int print_usage(const char *reason = nullptr);
|
||||||
|
|
||||||
void Run() override;
|
|
||||||
|
|
||||||
bool init();
|
bool init();
|
||||||
|
|
||||||
bool is_fixed_wing_requested();
|
bool is_fixed_wing_requested();
|
||||||
@@ -130,6 +128,8 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
void Run() override;
|
||||||
|
|
||||||
uORB::SubscriptionCallbackWorkItem _actuator_inputs_fw{this, ORB_ID(actuator_controls_virtual_fw)};
|
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::SubscriptionCallbackWorkItem _actuator_inputs_mc{this, ORB_ID(actuator_controls_virtual_mc)};
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user