mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: cope with AP_Scheduler not being available
This commit is contained in:
parent
9d470d4446
commit
fe9bcb9b5b
|
@ -367,9 +367,11 @@ void AP_Vehicle::setup()
|
||||||
networking.init();
|
networking.init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_SCHEDULER_ENABLED
|
||||||
// Register scheduler_delay_cb, which will run anytime you have
|
// Register scheduler_delay_cb, which will run anytime you have
|
||||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||||
hal.scheduler->register_delay_callback(scheduler_delay_callback, 5);
|
hal.scheduler->register_delay_callback(scheduler_delay_callback, 5);
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAL_MSP_ENABLED
|
#if HAL_MSP_ENABLED
|
||||||
// call MSP init before init_ardupilot to allow for MSP sensors
|
// call MSP init before init_ardupilot to allow for MSP sensors
|
||||||
|
@ -431,7 +433,11 @@ void AP_Vehicle::setup()
|
||||||
|
|
||||||
// gyro FFT needs to be initialized really late
|
// gyro FFT needs to be initialized really late
|
||||||
#if HAL_GYROFFT_ENABLED
|
#if HAL_GYROFFT_ENABLED
|
||||||
|
#if AP_SCHEDULER_ENABLED
|
||||||
gyro_fft.init(AP::scheduler().get_loop_rate_hz());
|
gyro_fft.init(AP::scheduler().get_loop_rate_hz());
|
||||||
|
#else
|
||||||
|
gyro_fft.init(1000);
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#if HAL_RUNCAM_ENABLED
|
#if HAL_RUNCAM_ENABLED
|
||||||
runcam.init();
|
runcam.init();
|
||||||
|
@ -520,8 +526,13 @@ void AP_Vehicle::setup()
|
||||||
|
|
||||||
void AP_Vehicle::loop()
|
void AP_Vehicle::loop()
|
||||||
{
|
{
|
||||||
|
#if AP_SCHEDULER_ENABLED
|
||||||
scheduler.loop();
|
scheduler.loop();
|
||||||
G_Dt = scheduler.get_loop_period_s();
|
G_Dt = scheduler.get_loop_period_s();
|
||||||
|
#else
|
||||||
|
hal.scheduler->delay(1);
|
||||||
|
G_Dt = 0.001;
|
||||||
|
#endif
|
||||||
|
|
||||||
if (!done_safety_init) {
|
if (!done_safety_init) {
|
||||||
/*
|
/*
|
||||||
|
@ -548,6 +559,7 @@ void AP_Vehicle::loop()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_SCHEDULER_ENABLED
|
||||||
/*
|
/*
|
||||||
scheduler table - all regular tasks apart from the fast_loop()
|
scheduler table - all regular tasks apart from the fast_loop()
|
||||||
should be listed here.
|
should be listed here.
|
||||||
|
@ -708,6 +720,7 @@ void AP_Vehicle::scheduler_delay_callback()
|
||||||
logger.EnableWrites(true);
|
logger.EnableWrites(true);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
#endif // AP_SCHEDULER_ENABLED
|
||||||
|
|
||||||
// if there's been a watchdog reset, notify the world via a statustext:
|
// if there's been a watchdog reset, notify the world via a statustext:
|
||||||
void AP_Vehicle::send_watchdog_reset_statustext()
|
void AP_Vehicle::send_watchdog_reset_statustext()
|
||||||
|
|
|
@ -127,10 +127,10 @@ public:
|
||||||
// parameters for example.
|
// parameters for example.
|
||||||
void notify_no_such_mode(uint8_t mode_number);
|
void notify_no_such_mode(uint8_t mode_number);
|
||||||
|
|
||||||
|
#if AP_SCHEDULER_ENABLED
|
||||||
void get_common_scheduler_tasks(const AP_Scheduler::Task*& tasks, uint8_t& num_tasks);
|
void get_common_scheduler_tasks(const AP_Scheduler::Task*& tasks, uint8_t& num_tasks);
|
||||||
// implementations *MUST* fill in all passed-in fields or we get
|
// implementations *MUST* fill in all passed-in fields or we get
|
||||||
// Valgrind errors
|
// Valgrind errors
|
||||||
#if AP_SCHEDULER_ENABLED
|
|
||||||
virtual void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) = 0;
|
virtual void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) = 0;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -310,8 +310,10 @@ protected:
|
||||||
AP_CANManager can_mgr;
|
AP_CANManager can_mgr;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_SCHEDULER_ENABLED
|
||||||
// main loop scheduler
|
// main loop scheduler
|
||||||
AP_Scheduler scheduler;
|
AP_Scheduler scheduler;
|
||||||
|
#endif
|
||||||
|
|
||||||
// IMU variables
|
// IMU variables
|
||||||
// Integration time; time last loop took to run
|
// Integration time; time last loop took to run
|
||||||
|
@ -461,7 +463,9 @@ protected:
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
#if AP_SCHEDULER_ENABLED
|
||||||
static const struct AP_Scheduler::Task scheduler_tasks[];
|
static const struct AP_Scheduler::Task scheduler_tasks[];
|
||||||
|
#endif
|
||||||
|
|
||||||
#if OSD_ENABLED
|
#if OSD_ENABLED
|
||||||
void publish_osd_info();
|
void publish_osd_info();
|
||||||
|
@ -495,8 +499,10 @@ protected:
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
#if AP_SCHEDULER_ENABLED
|
||||||
// delay() callback that processing MAVLink packets
|
// delay() callback that processing MAVLink packets
|
||||||
static void scheduler_delay_callback();
|
static void scheduler_delay_callback();
|
||||||
|
#endif
|
||||||
|
|
||||||
// if there's been a watchdog reset, notify the world via a
|
// if there's been a watchdog reset, notify the world via a
|
||||||
// statustext:
|
// statustext:
|
||||||
|
|
Loading…
Reference in New Issue