mirror of https://github.com/ArduPilot/ardupilot
Sub: let AP_Vehicle handle loop()
This commit is contained in:
parent
58d45ef04a
commit
7658c13c69
|
@ -91,13 +91,6 @@ void Sub::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
|
|||
|
||||
constexpr int8_t Sub::_failsafe_priorities[5];
|
||||
|
||||
void Sub::loop()
|
||||
{
|
||||
scheduler.loop();
|
||||
G_Dt = scheduler.get_loop_period_s();
|
||||
}
|
||||
|
||||
|
||||
// Main loop - 400hz
|
||||
void Sub::fast_loop()
|
||||
{
|
||||
|
|
|
@ -31,7 +31,6 @@ Sub::Sub()
|
|||
auto_mode(Auto_WP),
|
||||
guided_mode(Guided_WP),
|
||||
auto_yaw_mode(AUTO_YAW_LOOK_AT_NEXT_WP),
|
||||
G_Dt(MAIN_LOOP_SECONDS),
|
||||
inertial_nav(ahrs),
|
||||
ahrs_view(ahrs, ROTATION_NONE),
|
||||
attitude_control(ahrs_view, aparm, motors, MAIN_LOOP_SECONDS),
|
||||
|
|
|
@ -130,9 +130,6 @@ public:
|
|||
|
||||
Sub(void);
|
||||
|
||||
// HAL::Callbacks implementation.
|
||||
void loop() override;
|
||||
|
||||
private:
|
||||
|
||||
// key aircraft parameters passed to multiple libraries
|
||||
|
@ -142,9 +139,6 @@ private:
|
|||
Parameters g;
|
||||
ParametersG2 g2;
|
||||
|
||||
// main loop scheduler
|
||||
AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&Sub::fast_loop, void)};
|
||||
|
||||
// primary input control channels
|
||||
RC_Channel *channel_roll;
|
||||
RC_Channel *channel_pitch;
|
||||
|
@ -343,11 +337,6 @@ private:
|
|||
int32_t condition_value; // used in condition commands (eg delay, change alt, etc.)
|
||||
uint32_t condition_start;
|
||||
|
||||
// IMU variables
|
||||
// Integration time (in seconds) for the gyros (DCM algorithm)
|
||||
// Updated with the fast loop
|
||||
float G_Dt;
|
||||
|
||||
// Inertial Navigation
|
||||
AP_InertialNav_NavEKF inertial_nav;
|
||||
|
||||
|
@ -412,7 +401,7 @@ private:
|
|||
static const AP_Param::Info var_info[];
|
||||
static const struct LogStructure log_structure[];
|
||||
|
||||
void fast_loop();
|
||||
void fast_loop() override;
|
||||
void fifty_hz_loop();
|
||||
void update_batt_compass(void);
|
||||
void ten_hz_logging_loop();
|
||||
|
|
Loading…
Reference in New Issue