HAL_ChibiOS: make smaller builds possible

this allows for much smaller builds when you disable a lot of
options. This is part of an effort to create a bootloader of less than
16k using ChibiOS
This commit is contained in:
Andrew Tridgell 2018-03-07 09:41:03 +11:00
parent ea2dc9b831
commit e4ce2f532b
14 changed files with 97 additions and 50 deletions

View File

@ -15,6 +15,10 @@
* Code by Andrew Tridgell and Siddharth Bharat Purohit
*/
#include <AP_HAL/AP_HAL.h>
#include "ch.h"
#include "hal.h"
#if HAL_USE_ADC == TRUE
#include "AnalogIn.h"
@ -357,3 +361,5 @@ void AnalogIn::update_power_flags(void)
}
_power_flags = flags;
}
#endif // HAL_USE_ADC

View File

@ -24,6 +24,8 @@
// number of samples on each channel to gather on each DMA callback
#define ADC_DMA_BUF_DEPTH 8
#if HAL_USE_ADC == TRUE
class ChibiOS::AnalogSource : public AP_HAL::AnalogSource {
public:
friend class ChibiOS::AnalogIn;
@ -90,3 +92,5 @@ private:
static uint32_t sample_sum[];
static uint32_t sample_count;
};
#endif // HAL_USE_ADC

View File

@ -21,6 +21,7 @@
#include "Semaphores.h"
#include "Util.h"
#if HAL_USE_I2C == TRUE || HAL_USE_SPI == TRUE
using namespace ChibiOS;
@ -188,3 +189,5 @@ void DeviceBus::bouncebuffer_rx_copy(uint8_t *buf_rx, uint16_t rx_len)
{
memcpy(buf_rx, bounce_buffer_rx, rx_len);
}
#endif // HAL_USE_I2C || HAL_USE_SPI

View File

@ -15,10 +15,11 @@
* Code by Andrew Tridgell and Siddharth Bharat Purohit
*/
#include "GPIO.h"
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#include <AP_BoardConfig/AP_BoardConfig.h>
#if HAL_USE_EXT == TRUE
using namespace ChibiOS;
// GPIO pin table from hwdef.dat
@ -250,4 +251,4 @@ void ext_interrupt_cb(EXTDriver *extp, expchannel_t channel)
}
}
#endif //HAL_BOARD_ChibiOS
#endif // HAL_USE_EXT

View File

@ -23,6 +23,7 @@
#include <AP_HAL_Empty/AP_HAL_Empty_Private.h>
#include <AP_HAL_ChibiOS/AP_HAL_ChibiOS_Private.h>
#include "shared_dma.h"
#include "hwdef/common/usbcfg.h"
#include <hwdef.h>
@ -45,7 +46,12 @@ static ChibiOS::SPIDeviceManager spiDeviceManager;
static Empty::SPIDeviceManager spiDeviceManager;
#endif
#if HAL_USE_ADC == TRUE
static ChibiOS::AnalogIn analogIn;
#else
static Empty::AnalogIn analogIn;
#endif
#ifdef HAL_USE_EMPTY_STORAGE
static Empty::Storage storageDriver;
#else
@ -108,10 +114,12 @@ extern const AP_HAL::HAL& hal;
void hal_chibios_set_priority(uint8_t priority)
{
chSysLock();
#if CH_CFG_USE_MUTEXES == TRUE
if ((daemon_task->prio == daemon_task->realprio) || (priority > daemon_task->prio)) {
daemon_task->prio = priority;
}
daemon_task->realprio = priority;
#endif
chSchRescheduleS();
chSysUnlock();
}
@ -158,7 +166,8 @@ static THD_FUNCTION(main_loop,arg)
hal.scheduler->system_initialized();
thread_running = true;
daemon_task->name = SKETCHNAME;
chRegSetThreadName(SKETCHNAME);
/*
switch to high priority for main loop
*/
@ -192,6 +201,10 @@ void HAL_ChibiOS::run(int argc, char * const argv[], Callbacks* callbacks) const
* RTOS is active.
*/
#ifdef HAL_USB_PRODUCT_ID
setup_usb_strings();
#endif
#ifdef HAL_STDOUT_SERIAL
//STDOUT Initialistion
SerialConfig stdoutcfg =

View File

@ -35,7 +35,6 @@ void RCInput::init()
sig_reader.attach_capture_timer(&RCIN_ICU_TIMER, RCIN_ICU_CHANNEL, STM32_RCIN_DMA_STREAM, STM32_RCIN_DMA_CHANNEL);
rcin_prot.init();
#endif
chMtxObjectInit(&rcin_mutex);
_init = true;
}
@ -44,7 +43,9 @@ bool RCInput::new_input()
if (!_init) {
return false;
}
chMtxLock(&rcin_mutex);
if (!rcin_mutex.take_nonblocking()) {
return false;
}
bool valid = _rcin_timestamp_last_signal != _last_read;
if (_override_valid) {
@ -53,7 +54,7 @@ bool RCInput::new_input()
}
_last_read = _rcin_timestamp_last_signal;
_override_valid = false;
chMtxUnlock(&rcin_mutex);
rcin_mutex.give();
#ifdef HAL_RCINPUT_WITH_AP_RADIO
if (!_radio_init) {
@ -72,10 +73,7 @@ uint8_t RCInput::num_channels()
if (!_init) {
return 0;
}
chMtxLock(&rcin_mutex);
uint8_t n = _num_channels;
chMtxUnlock(&rcin_mutex);
return n;
return _num_channels;
}
uint16_t RCInput::read(uint8_t channel)
@ -86,18 +84,18 @@ uint16_t RCInput::read(uint8_t channel)
if (channel >= RC_INPUT_MAX_CHANNELS) {
return 0;
}
chMtxLock(&rcin_mutex);
rcin_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER);
if (_override[channel]) {
uint16_t v = _override[channel];
chMtxUnlock(&rcin_mutex);
rcin_mutex.give();
return v;
}
if (channel >= _num_channels) {
chMtxUnlock(&rcin_mutex);
rcin_mutex.give();
return 0;
}
uint16_t v = _rc_values[channel];
chMtxUnlock(&rcin_mutex);
rcin_mutex.give();
#ifdef HAL_RCINPUT_WITH_AP_RADIO
if (radio && channel == 0) {
// hook to allow for update of radio on main thread, for mavlink sends
@ -176,36 +174,36 @@ void RCInput::_timer_tick(void)
}
if (rcin_prot.new_input()) {
chMtxLock(&rcin_mutex);
rcin_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER);
_rcin_timestamp_last_signal = AP_HAL::micros();
_num_channels = rcin_prot.num_channels();
for (uint8_t i=0; i<_num_channels; i++) {
_rc_values[i] = rcin_prot.read(i);
}
chMtxUnlock(&rcin_mutex);
rcin_mutex.give();
}
#endif
#ifdef HAL_RCINPUT_WITH_AP_RADIO
if (radio && radio->last_recv_us() != last_radio_us) {
last_radio_us = radio->last_recv_us();
chMtxLock(&rcin_mutex);
rcin_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER);
_rcin_timestamp_last_signal = last_radio_us;
_num_channels = radio->num_channels();
for (uint8_t i=0; i<_num_channels; i++) {
_rc_values[i] = radio->read(i);
}
chMtxUnlock(&rcin_mutex);
rcin_mutex.give();
}
#endif
#if HAL_WITH_IO_MCU
chMtxLock(&rcin_mutex);
rcin_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER);
if (AP_BoardConfig::io_enabled() &&
iomcu.check_rcinput(last_iomcu_us, _num_channels, _rc_values, RC_INPUT_MAX_CHANNELS)) {
_rcin_timestamp_last_signal = last_iomcu_us;
}
chMtxUnlock(&rcin_mutex);
rcin_mutex.give();
#endif

View File

@ -18,6 +18,7 @@
#include "AP_HAL_ChibiOS.h"
#include "SoftSigReader.h"
#include "Semaphores.h"
#ifdef HAL_RCINPUT_WITH_AP_RADIO
#include <AP_Radio/AP_Radio.h>
@ -59,7 +60,7 @@ private:
uint64_t _last_read;
bool _override_valid;
uint8_t _num_channels;
mutex_t rcin_mutex;
Semaphore rcin_mutex;
int16_t _rssi = -1;
uint32_t _rcin_timestamp_last_signal;
bool _init;

View File

@ -15,7 +15,6 @@
* Code by Andrew Tridgell and Siddharth Bharat Purohit
*/
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#include "AP_HAL_ChibiOS.h"
#include "Scheduler.h"
@ -32,6 +31,8 @@
#include <AP_BoardConfig/AP_BoardConfig.h>
#include "shared_dma.h"
#if CH_CFG_USE_DYNAMIC == TRUE
using namespace ChibiOS;
extern const AP_HAL::HAL& hal;
@ -285,8 +286,10 @@ void Scheduler::_run_timers(bool called_from_timer_thread)
_failsafe();
}
#if HAL_USE_ADC == TRUE
// process analog input
((AnalogIn *)hal.analogin)->_timer_tick();
#endif
_in_timer_proc = false;
}
@ -294,7 +297,7 @@ void Scheduler::_run_timers(bool called_from_timer_thread)
void Scheduler::_timer_thread(void *arg)
{
Scheduler *sched = (Scheduler *)arg;
sched->_timer_thread_ctx->name = "apm_timer";
chRegSetThreadName("apm_timer");
while (!sched->_hal_initialized) {
sched->delay_microseconds(1000);
@ -313,7 +316,7 @@ void Scheduler::_timer_thread(void *arg)
void Scheduler::_uavcan_thread(void *arg)
{
Scheduler *sched = (Scheduler *)arg;
sched->_uavcan_thread_ctx->name = "apm_uavcan";
chRegSetThreadName("apm_uavcan");
while (!sched->_hal_initialized) {
sched->delay_microseconds(20000);
}
@ -331,7 +334,7 @@ void Scheduler::_uavcan_thread(void *arg)
void Scheduler::_rcin_thread(void *arg)
{
Scheduler *sched = (Scheduler *)arg;
sched->_rcin_thread_ctx->name = "apm_rcin";
chRegSetThreadName("apm_rcin");
while (!sched->_hal_initialized) {
sched->delay_microseconds(20000);
}
@ -345,7 +348,7 @@ void Scheduler::_rcin_thread(void *arg)
void Scheduler::_toneAlarm_thread(void *arg)
{
Scheduler *sched = (Scheduler *)arg;
sched->_toneAlarm_thread_ctx->name = "toneAlarm";
chRegSetThreadName("toneAlarm");
while (!sched->_hal_initialized) {
sched->delay_microseconds(20000);
}
@ -379,7 +382,7 @@ void Scheduler::_run_io(void)
void Scheduler::_io_thread(void* arg)
{
Scheduler *sched = (Scheduler *)arg;
sched->_io_thread_ctx->name = "apm_io";
chRegSetThreadName("apm_io");
while (!sched->_hal_initialized) {
sched->delay_microseconds(1000);
}
@ -394,7 +397,7 @@ void Scheduler::_io_thread(void* arg)
void Scheduler::_storage_thread(void* arg)
{
Scheduler *sched = (Scheduler *)arg;
sched->_storage_thread_ctx->name = "apm_storage";
chRegSetThreadName("apm_storage");
while (!sched->_hal_initialized) {
sched->delay_microseconds(10000);
}
@ -438,4 +441,4 @@ void Scheduler::restore_interrupts(void *state)
chSysRestoreStatusX((syssts_t)(uintptr_t)state);
}
#endif
#endif // CH_CFG_USE_DYNAMIC

View File

@ -15,11 +15,10 @@
* Code by Andrew Tridgell and Siddharth Bharat Purohit
*/
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#include "Semaphores.h"
#if CH_CFG_USE_MUTEXES == TRUE
extern const AP_HAL::HAL& hal;
using namespace ChibiOS;
@ -54,4 +53,5 @@ bool Semaphore::take_nonblocking()
return chMtxTryLock(&_lock);
}
#endif // CONFIG_HAL_BOARD
#endif // CH_CFG_USE_MUTEXES

View File

@ -18,19 +18,25 @@
#include <AP_HAL/AP_HAL_Boards.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#include "AP_HAL_ChibiOS.h"
class ChibiOS::Semaphore : public AP_HAL::Semaphore {
public:
Semaphore() {
#if CH_CFG_USE_MUTEXES == TRUE
chMtxObjectInit(&_lock);
#endif
}
bool give();
bool take(uint32_t timeout_ms);
bool take_nonblocking();
bool check_owner(void) {
#if CH_CFG_USE_MUTEXES == TRUE
return _lock.owner == chThdGetSelfX();
#else
return true;
#endif
}
void assert_owner(void) {
osalDbgAssert(check_owner(), "owner");
@ -38,4 +44,3 @@ public:
private:
mutex_t _lock;
};
#endif // CONFIG_HAL_BOARD

View File

@ -62,7 +62,6 @@ _initialised(false)
{
osalDbgAssert(serial_num < UART_MAX_DRIVERS, "too many UART drivers");
uart_drivers[serial_num] = this;
chMtxObjectInit(&_write_mutex);
}
/*
@ -104,12 +103,14 @@ void UARTDriver::thread_init(void)
// already initialised
return;
}
#if CH_CFG_USE_HEAP == TRUE
uart_thread_ctx = chThdCreateFromHeap(NULL,
THD_WORKING_AREA_SIZE(2048),
"apm_uart",
APM_UART_PRIORITY,
uart_thread,
this);
#endif
}
@ -447,18 +448,18 @@ int16_t UARTDriver::read()
/* Empty implementations of Print virtual methods */
size_t UARTDriver::write(uint8_t c)
{
if (lock_key != 0 || !chMtxTryLock(&_write_mutex)) {
if (lock_key != 0 || !_write_mutex.take_nonblocking()) {
return 0;
}
if (!_initialised) {
chMtxUnlock(&_write_mutex);
_write_mutex.give();
return 0;
}
while (_writebuf.space() == 0) {
if (!_blocking_writes) {
chMtxUnlock(&_write_mutex);
_write_mutex.give();
return 0;
}
hal.scheduler->delay(1);
@ -467,7 +468,7 @@ size_t UARTDriver::write(uint8_t c)
if (unbuffered_writes) {
write_pending_bytes();
}
chMtxUnlock(&_write_mutex);
_write_mutex.give();
return ret;
}
@ -477,7 +478,7 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
return 0;
}
if (!chMtxTryLock(&_write_mutex)) {
if (!_write_mutex.take_nonblocking()) {
return 0;
}
@ -485,7 +486,7 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
/*
use the per-byte delay loop in write() above for blocking writes
*/
chMtxUnlock(&_write_mutex);
_write_mutex.give();
size_t ret = 0;
while (size--) {
if (write(*buffer++) != 1) break;
@ -498,7 +499,7 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
if (unbuffered_writes) {
write_pending_bytes();
}
chMtxUnlock(&_write_mutex);
_write_mutex.give();
return ret;
}
@ -524,12 +525,12 @@ size_t UARTDriver::write_locked(const uint8_t *buffer, size_t size, uint32_t key
if (lock_key != 0 && key != lock_key) {
return 0;
}
if (!chMtxTryLock(&_write_mutex)) {
if (!_write_mutex.take_nonblocking()) {
return 0;
}
size_t ret = _writebuf.write(buffer, size);
chMtxUnlock(&_write_mutex);
_write_mutex.give();
return ret;
}
@ -774,9 +775,9 @@ void UARTDriver::_timer_tick(void)
// provided by the write() call, but if the write is larger
// than the DMA buffer size then there can be extra bytes to
// send here, and they must be sent with the write lock held
chMtxLock(&_write_mutex);
_write_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER);
write_pending_bytes();
chMtxUnlock(&_write_mutex);
_write_mutex.give();
} else {
write_pending_bytes();
}

View File

@ -20,6 +20,7 @@
#include "AP_HAL_ChibiOS.h"
#include "shared_dma.h"
#include "Semaphores.h"
#define RX_BOUNCE_BUFSIZE 128
#define TX_BOUNCE_BUFSIZE 64
@ -119,7 +120,7 @@ private:
uint8_t tx_bounce_buf[TX_BOUNCE_BUFSIZE];
ByteBuffer _readbuf{0};
ByteBuffer _writebuf{0};
mutex_t _write_mutex;
Semaphore _write_mutex;
const stm32_dma_stream_t* rxdma;
const stm32_dma_stream_t* txdma;
bool _in_timer;

View File

@ -17,7 +17,6 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#include "Util.h"
#include <chheap.h>
#include "ToneAlarm.h"
@ -32,6 +31,8 @@ extern const AP_HAL::HAL& hal;
using namespace ChibiOS;
#if CH_CFG_USE_HEAP == TRUE
extern "C" {
size_t mem_available(void);
void *malloc_ccm(size_t size);
@ -77,6 +78,8 @@ void* Util::try_alloc_from_ccm_ram(size_t size)
return ret;
}
#endif // CH_CFG_USE_HEAP
/*
get safety switch state
*/
@ -177,4 +180,4 @@ void Util::_toneAlarm_timer_tick() {
}
#endif // HAL_PWM_ALARM
#endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS

View File

@ -28,6 +28,10 @@
*/
#pragma once
#if defined(__cplusplus)
extern "C" {
#endif
#if HAL_USE_SERIAL_USB
extern const USBConfig usbcfg;
extern SerialUSBConfig serusbcfg;
@ -36,4 +40,8 @@ extern SerialUSBDriver SDU1;
void setup_usb_strings(void);
#if defined(__cplusplus)
}
#endif
/** @} */