mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Blimp: add option to disable relay and servorelay libraries
This commit is contained in:
parent
d9e89eb602
commit
ccd39efe1c
@ -72,7 +72,9 @@ const AP_Scheduler::Task Blimp::scheduler_tasks[] = {
|
|||||||
SCHED_TASK(arm_motors_check, 10, 50, 18),
|
SCHED_TASK(arm_motors_check, 10, 50, 18),
|
||||||
SCHED_TASK(update_altitude, 10, 100, 21),
|
SCHED_TASK(update_altitude, 10, 100, 21),
|
||||||
SCHED_TASK(three_hz_loop, 3, 75, 24),
|
SCHED_TASK(three_hz_loop, 3, 75, 24),
|
||||||
|
#if AP_SERVORELAYEVENTS_ENABLED
|
||||||
SCHED_TASK_CLASS(AP_ServoRelayEvents, &blimp.ServoRelayEvents, update_events, 50, 75, 27),
|
SCHED_TASK_CLASS(AP_ServoRelayEvents, &blimp.ServoRelayEvents, update_events, 50, 75, 27),
|
||||||
|
#endif
|
||||||
SCHED_TASK_CLASS(AP_Baro, &blimp.barometer, accumulate, 50, 90, 30),
|
SCHED_TASK_CLASS(AP_Baro, &blimp.barometer, accumulate, 50, 90, 30),
|
||||||
#if LOGGING_ENABLED == ENABLED
|
#if LOGGING_ENABLED == ENABLED
|
||||||
SCHED_TASK(full_rate_logging, 50, 50, 33),
|
SCHED_TASK(full_rate_logging, 50, 50, 33),
|
||||||
|
@ -58,7 +58,9 @@ void Blimp::init_ardupilot()
|
|||||||
// motors initialised so parameters can be sent
|
// motors initialised so parameters can be sent
|
||||||
ap.initialised_params = true;
|
ap.initialised_params = true;
|
||||||
|
|
||||||
|
#if AP_RELAY_ENABLED
|
||||||
relay.init();
|
relay.init();
|
||||||
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* setup the 'main loop is dead' check. Note that this relies on
|
* setup the 'main loop is dead' check. Note that this relies on
|
||||||
|
Loading…
Reference in New Issue
Block a user