mirror of https://github.com/ArduPilot/ardupilot
Copter: let AP_Vehicle handle loop()
This commit is contained in:
parent
449ca74951
commit
18670d681e
|
@ -220,13 +220,6 @@ void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
|
|||
|
||||
constexpr int8_t Copter::_failsafe_priorities[7];
|
||||
|
||||
void Copter::loop()
|
||||
{
|
||||
scheduler.loop();
|
||||
G_Dt = scheduler.get_last_loop_time_s();
|
||||
}
|
||||
|
||||
|
||||
// Main loop - 400hz
|
||||
void Copter::fast_loop()
|
||||
{
|
||||
|
|
|
@ -56,7 +56,6 @@
|
|||
#include <AC_WPNav/AC_Loiter.h>
|
||||
#include <AC_WPNav/AC_Circle.h> // circle navigation library
|
||||
#include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
|
||||
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
|
||||
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
||||
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
|
||||
|
@ -234,9 +233,6 @@ public:
|
|||
|
||||
Copter(void);
|
||||
|
||||
// HAL::Callbacks implementation.
|
||||
void loop() override;
|
||||
|
||||
private:
|
||||
|
||||
// key aircraft parameters passed to multiple libraries
|
||||
|
@ -246,9 +242,6 @@ private:
|
|||
Parameters g;
|
||||
ParametersG2 g2;
|
||||
|
||||
// main loop scheduler
|
||||
AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&Copter::fast_loop, void)};
|
||||
|
||||
// used to detect MAVLink acks from GCS to stop compassmot
|
||||
uint8_t command_ack_counter;
|
||||
|
||||
|
@ -458,11 +451,6 @@ private:
|
|||
// Current location of the vehicle (altitude is relative to home)
|
||||
Location current_loc;
|
||||
|
||||
// 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;
|
||||
|
||||
|
@ -641,7 +629,7 @@ private:
|
|||
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
|
||||
uint8_t &task_count,
|
||||
uint32_t &log_bit) override;
|
||||
void fast_loop();
|
||||
void fast_loop() override;
|
||||
void rc_loop();
|
||||
void throttle_loop();
|
||||
void update_batt_compass(void);
|
||||
|
|
|
@ -15,9 +15,6 @@ static void failsafe_check_static()
|
|||
|
||||
void Copter::init_ardupilot()
|
||||
{
|
||||
// time per loop - this gets updated in the main loop() based on
|
||||
// actual loop rate
|
||||
G_Dt = 1.0 / scheduler.get_loop_rate_hz();
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
// initialise stats module
|
||||
|
|
Loading…
Reference in New Issue