mirror of https://github.com/ArduPilot/ardupilot
AP_Scheduler: correct compilation when AP_Vehicle not available
This commit is contained in:
parent
105acc605f
commit
0f4262de3d
|
@ -31,6 +31,7 @@
|
||||||
#include <AP_InternalError/AP_InternalError.h>
|
#include <AP_InternalError/AP_InternalError.h>
|
||||||
#include <AP_Common/ExpandingString.h>
|
#include <AP_Common/ExpandingString.h>
|
||||||
#include <AP_HAL/SIMState.h>
|
#include <AP_HAL/SIMState.h>
|
||||||
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
#include <SITL/SITL.h>
|
#include <SITL/SITL.h>
|
||||||
|
@ -113,10 +114,12 @@ void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks, uint
|
||||||
_vehicle_tasks = tasks;
|
_vehicle_tasks = tasks;
|
||||||
_num_vehicle_tasks = num_tasks;
|
_num_vehicle_tasks = num_tasks;
|
||||||
|
|
||||||
|
#if AP_VEHICLE_ENABLED
|
||||||
AP_Vehicle* vehicle = AP::vehicle();
|
AP_Vehicle* vehicle = AP::vehicle();
|
||||||
if (vehicle != nullptr) {
|
if (vehicle != nullptr) {
|
||||||
vehicle->get_common_scheduler_tasks(_common_tasks, _num_common_tasks);
|
vehicle->get_common_scheduler_tasks(_common_tasks, _num_common_tasks);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
_num_tasks = _num_vehicle_tasks + _num_common_tasks;
|
_num_tasks = _num_vehicle_tasks + _num_common_tasks;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue