HAL_ChibiOS: disable segments relating to unused features

This commit is contained in:
Siddharth Purohit 2018-08-29 18:44:45 +05:30 committed by Andrew Tridgell
parent 87a2dea9d4
commit b9319cae56
2 changed files with 33 additions and 7 deletions

View File

@ -39,11 +39,14 @@
using namespace ChibiOS; using namespace ChibiOS;
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
THD_WORKING_AREA(_timer_thread_wa, 2048); THD_WORKING_AREA(_timer_thread_wa, TIMER_THD_WA_SIZE);
THD_WORKING_AREA(_rcin_thread_wa, 512); THD_WORKING_AREA(_rcin_thread_wa, RCIN_THD_WA_SIZE);
THD_WORKING_AREA(_io_thread_wa, 2048); #ifndef HAL_USE_EMPTY_IO
THD_WORKING_AREA(_storage_thread_wa, 2048); THD_WORKING_AREA(_io_thread_wa, IO_THD_WA_SIZE);
#endif
#ifndef HAL_USE_EMPTY_STORAGE
THD_WORKING_AREA(_storage_thread_wa, STORAGE_THD_WA_SIZE);
#endif
Scheduler::Scheduler() Scheduler::Scheduler()
{ {
} }
@ -65,20 +68,24 @@ void Scheduler::init()
APM_RCIN_PRIORITY, /* Initial priority. */ APM_RCIN_PRIORITY, /* Initial priority. */
_rcin_thread, /* Thread function. */ _rcin_thread, /* Thread function. */
this); /* Thread parameter. */ this); /* Thread parameter. */
#ifndef HAL_USE_EMPTY_IO
// the IO thread runs at lower priority // the IO thread runs at lower priority
_io_thread_ctx = chThdCreateStatic(_io_thread_wa, _io_thread_ctx = chThdCreateStatic(_io_thread_wa,
sizeof(_io_thread_wa), sizeof(_io_thread_wa),
APM_IO_PRIORITY, /* Initial priority. */ APM_IO_PRIORITY, /* Initial priority. */
_io_thread, /* Thread function. */ _io_thread, /* Thread function. */
this); /* Thread parameter. */ this); /* Thread parameter. */
#endif
#ifndef HAL_USE_EMPTY_STORAGE
// the storage thread runs at just above IO priority // the storage thread runs at just above IO priority
_storage_thread_ctx = chThdCreateStatic(_storage_thread_wa, _storage_thread_ctx = chThdCreateStatic(_storage_thread_wa,
sizeof(_storage_thread_wa), sizeof(_storage_thread_wa),
APM_STORAGE_PRIORITY, /* Initial priority. */ APM_STORAGE_PRIORITY, /* Initial priority. */
_storage_thread, /* Thread function. */ _storage_thread, /* Thread function. */
this); /* Thread parameter. */ this); /* Thread parameter. */
#endif
} }
@ -209,14 +216,18 @@ void Scheduler::reboot(bool hold_in_bootloader)
// disarm motors to ensure they are off during a bootloader upload // disarm motors to ensure they are off during a bootloader upload
hal.rcout->force_safety_on(); hal.rcout->force_safety_on();
#ifndef NO_DATAFLASH
//stop logging //stop logging
DataFlash_Class::instance()->StopLogging(); DataFlash_Class::instance()->StopLogging();
// stop sdcard driver, if active // stop sdcard driver, if active
sdcard_stop(); sdcard_stop();
#endif
#if defined(HAL_USE_RTC) && HAL_USE_RTC
// setup RTC for fast reboot // setup RTC for fast reboot
set_fast_reboot(hold_in_bootloader?RTC_BOOT_HOLD:RTC_BOOT_FAST); set_fast_reboot(hold_in_bootloader?RTC_BOOT_HOLD:RTC_BOOT_FAST);
#endif
// disable all interrupt sources // disable all interrupt sources
port_disable(); port_disable();

View File

@ -51,7 +51,22 @@
#define APM_I2C_PRIORITY 176 #define APM_I2C_PRIORITY 176
#endif #endif
#define APM_MAIN_THREAD_STACK_SIZE 8192 #ifndef TIMER_THD_WA_SIZE
#define TIMER_THD_WA_SIZE 2048
#endif
#ifndef RCIN_THD_WA_SIZE
#define RCIN_THD_WA_SIZE 512
#endif
#ifndef IO_THD_WA_SIZE
#define IO_THD_WA_SIZE 2048
#endif
#ifndef STORAGE_THD_WA_SIZE
#define STORAGE_THD_WA_SIZE 2048
#endif
/* Scheduler implementation: */ /* Scheduler implementation: */
class ChibiOS::Scheduler : public AP_HAL::Scheduler { class ChibiOS::Scheduler : public AP_HAL::Scheduler {