HAL_ChibiOS: resync for 4.0 update
This commit is contained in:
parent
a426964349
commit
31f7b32fab
@ -13,7 +13,6 @@ namespace ChibiOS {
|
||||
class RCOutput;
|
||||
class Scheduler;
|
||||
class Semaphore;
|
||||
class Semaphore_Recursive;
|
||||
class SPIBus;
|
||||
class SPIDesc;
|
||||
class SPIDevice;
|
||||
|
@ -69,14 +69,8 @@ adcsample_t *AnalogIn::samples;
|
||||
uint32_t AnalogIn::sample_sum[ADC_GRP1_NUM_CHANNELS];
|
||||
uint32_t AnalogIn::sample_count;
|
||||
|
||||
AnalogSource::AnalogSource(int16_t pin, float initial_value) :
|
||||
_pin(pin),
|
||||
_value(initial_value),
|
||||
_value_ratiometric(initial_value),
|
||||
_latest_value(initial_value),
|
||||
_sum_count(0),
|
||||
_sum_value(0),
|
||||
_sum_ratiometric(0)
|
||||
AnalogSource::AnalogSource(int16_t pin) :
|
||||
_pin(pin)
|
||||
{
|
||||
}
|
||||
|
||||
@ -351,7 +345,7 @@ AP_HAL::AnalogSource* AnalogIn::channel(int16_t pin)
|
||||
{
|
||||
for (uint8_t j=0; j<ANALOG_MAX_CHANNELS; j++) {
|
||||
if (_channels[j] == nullptr) {
|
||||
_channels[j] = new AnalogSource(pin, 0.0f);
|
||||
_channels[j] = new AnalogSource(pin);
|
||||
return _channels[j];
|
||||
}
|
||||
}
|
||||
|
@ -29,7 +29,7 @@
|
||||
class ChibiOS::AnalogSource : public AP_HAL::AnalogSource {
|
||||
public:
|
||||
friend class ChibiOS::AnalogIn;
|
||||
AnalogSource(int16_t pin, float initial_value);
|
||||
AnalogSource(int16_t pin);
|
||||
float read_average() override;
|
||||
float read_latest() override;
|
||||
void set_pin(uint8_t p) override;
|
||||
@ -67,11 +67,6 @@ private:
|
||||
void read_adc(uint32_t *val);
|
||||
void update_power_flags(void);
|
||||
|
||||
int _battery_handle;
|
||||
int _servorail_handle;
|
||||
int _system_power_handle;
|
||||
uint64_t _battery_timestamp;
|
||||
uint64_t _servorail_timestamp;
|
||||
ChibiOS::AnalogSource* _channels[ANALOG_MAX_CHANNELS];
|
||||
|
||||
uint32_t _last_run;
|
||||
|
@ -69,6 +69,8 @@
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
static_assert(STM32_FDCANCLK <= 80U*1000U*1000U, "FDCAN clock must be max 80MHz");
|
||||
|
||||
namespace ChibiOS_CAN
|
||||
{
|
||||
namespace
|
||||
@ -200,7 +202,8 @@ int CanIface::computeTimings(const uavcan::uint32_t target_bitrate, Timings& out
|
||||
/*
|
||||
* Hardware configuration
|
||||
*/
|
||||
const uavcan::uint32_t pclk = STM32_PLL1_Q_CK;
|
||||
const uavcan::uint32_t pclk = STM32_FDCANCLK;
|
||||
|
||||
|
||||
static const int MaxBS1 = 16;
|
||||
static const int MaxBS2 = 8;
|
||||
|
@ -117,12 +117,16 @@ void SLCANRouter::slcan2can_router_trampoline(void)
|
||||
}
|
||||
chSysUnlock();
|
||||
_slcan_if.reader();
|
||||
if (_can_tx_queue.available() && _can_if) {
|
||||
while (_can_tx_queue.available() && _can_if) {
|
||||
_can_tx_queue.peek(it);
|
||||
if (_can_if->send(it.frame, uavcan::MonotonicTime::fromUSec(AP_HAL::micros64() + 1000), 0)) {
|
||||
_can_tx_queue.pop();
|
||||
} else {
|
||||
break;
|
||||
}
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
}
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
}
|
||||
}
|
||||
|
||||
@ -137,12 +141,16 @@ void SLCANRouter::can2slcan_router_trampoline(void)
|
||||
}
|
||||
chSysUnlock();
|
||||
_update_event->wait(uavcan::MonotonicDuration::fromUSec(1000));
|
||||
if (_slcan_tx_queue.available()) {
|
||||
while (_slcan_tx_queue.available()) {
|
||||
_slcan_tx_queue.peek(it);
|
||||
if (_slcan_if.send(it.frame, uavcan::MonotonicTime::fromUSec(AP_HAL::micros64() + 1000), 0)) {
|
||||
_slcan_tx_queue.pop();
|
||||
} else {
|
||||
break;
|
||||
}
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
}
|
||||
hal.scheduler->delay_microseconds(100);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -58,10 +58,8 @@ void DeviceBus::bus_thread(void *arg)
|
||||
callback->next_usec += callback->period_usec;
|
||||
}
|
||||
// call it with semaphore held
|
||||
if (binfo->semaphore.take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
callback->cb();
|
||||
binfo->semaphore.give();
|
||||
}
|
||||
WITH_SEMAPHORE(binfo->semaphore);
|
||||
callback->cb();
|
||||
}
|
||||
}
|
||||
|
||||
@ -106,12 +104,12 @@ AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t pe
|
||||
char *name = (char *)malloc(name_len);
|
||||
switch (hal_device->bus_type()) {
|
||||
case AP_HAL::Device::BUS_TYPE_I2C:
|
||||
snprintf(name, name_len, "I2C:%u",
|
||||
snprintf(name, name_len, "I2C%u",
|
||||
hal_device->bus_num());
|
||||
break;
|
||||
|
||||
case AP_HAL::Device::BUS_TYPE_SPI:
|
||||
snprintf(name, name_len, "SPI:%u",
|
||||
snprintf(name, name_len, "SPI%u",
|
||||
hal_device->bus_num());
|
||||
break;
|
||||
default:
|
||||
|
@ -30,6 +30,7 @@ static struct gpio_entry {
|
||||
AP_HAL::GPIO::irq_handler_fn_t fn; // callback for GPIO interface
|
||||
bool is_input;
|
||||
uint8_t mode;
|
||||
thread_reference_t thd_wait;
|
||||
} _gpio_tab[] = HAL_GPIO_PINS;
|
||||
|
||||
#define NUM_PINS ARRAY_SIZE(_gpio_tab)
|
||||
@ -67,8 +68,47 @@ void GPIO::init()
|
||||
g->enabled = g->pwm_num > pwm_count;
|
||||
}
|
||||
}
|
||||
#ifdef HAL_PIN_ALT_CONFIG
|
||||
setup_alt_config();
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef HAL_PIN_ALT_CONFIG
|
||||
/*
|
||||
alternative config table, selected using BRD_ALT_CONFIG
|
||||
*/
|
||||
static const struct alt_config {
|
||||
uint8_t alternate;
|
||||
uint16_t mode;
|
||||
ioline_t line;
|
||||
} alternate_config[] HAL_PIN_ALT_CONFIG;
|
||||
|
||||
/*
|
||||
change pin configuration based on ALT() lines in hwdef.dat
|
||||
*/
|
||||
void GPIO::setup_alt_config(void)
|
||||
{
|
||||
AP_BoardConfig *bc = AP::boardConfig();
|
||||
if (!bc) {
|
||||
return;
|
||||
}
|
||||
const uint8_t alt = bc->get_alt_config();
|
||||
if (alt == 0) {
|
||||
// use defaults
|
||||
return;
|
||||
}
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(alternate_config); i++) {
|
||||
if (alt == alternate_config[i].alternate) {
|
||||
const iomode_t mode = alternate_config[i].mode & ~PAL_STM32_HIGH;
|
||||
const uint8_t odr = (alternate_config[i].mode & PAL_STM32_HIGH)?1:0;
|
||||
palSetLineMode(alternate_config[i].line, mode);
|
||||
palWriteLine(alternate_config[i].line, odr);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // HAL_PIN_ALT_CONFIG
|
||||
|
||||
|
||||
void GPIO::pinMode(uint8_t pin, uint8_t output)
|
||||
{
|
||||
struct gpio_entry *g = gpio_by_pin_num(pin);
|
||||
@ -180,7 +220,7 @@ bool GPIO::attach_interrupt(uint8_t pin,
|
||||
return _attach_interrupt(g->pal_line, proc, mode);
|
||||
}
|
||||
|
||||
bool GPIO::_attach_interrupt(ioline_t line, palcallback_t cb, void *p, uint8_t mode)
|
||||
bool GPIO::_attach_interruptI(ioline_t line, palcallback_t cb, void *p, uint8_t mode)
|
||||
{
|
||||
uint32_t chmode = 0;
|
||||
switch(mode) {
|
||||
@ -200,11 +240,9 @@ bool GPIO::_attach_interrupt(ioline_t line, palcallback_t cb, void *p, uint8_t m
|
||||
break;
|
||||
}
|
||||
|
||||
osalSysLock();
|
||||
palevent_t *pep = pal_lld_get_line_event(line);
|
||||
if (pep->cb && p != nullptr) {
|
||||
// the pad is already being used for a callback
|
||||
osalSysUnlock();
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -215,11 +253,18 @@ bool GPIO::_attach_interrupt(ioline_t line, palcallback_t cb, void *p, uint8_t m
|
||||
palDisableLineEventI(line);
|
||||
palSetLineCallbackI(line, cb, p);
|
||||
palEnableLineEventI(line, chmode);
|
||||
osalSysUnlock();
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool GPIO::_attach_interrupt(ioline_t line, palcallback_t cb, void *p, uint8_t mode)
|
||||
{
|
||||
osalSysLock();
|
||||
bool ret = _attach_interruptI(line, cb, p, mode);
|
||||
osalSysUnlock();
|
||||
return ret;
|
||||
}
|
||||
|
||||
bool GPIO::usb_connected(void)
|
||||
{
|
||||
return _usb_connected;
|
||||
@ -249,14 +294,14 @@ void DigitalSource::toggle()
|
||||
palToggleLine(line);
|
||||
}
|
||||
|
||||
void pal_interrupt_cb(void *arg)
|
||||
static void pal_interrupt_cb(void *arg)
|
||||
{
|
||||
if (arg != nullptr) {
|
||||
((AP_HAL::Proc)arg)();
|
||||
}
|
||||
}
|
||||
|
||||
void pal_interrupt_cb_functor(void *arg)
|
||||
static void pal_interrupt_cb_functor(void *arg)
|
||||
{
|
||||
const uint32_t now = AP_HAL::micros();
|
||||
|
||||
@ -270,3 +315,54 @@ void pal_interrupt_cb_functor(void *arg)
|
||||
}
|
||||
(g->fn)(g->pin_num, palReadLine(g->pal_line), now);
|
||||
}
|
||||
|
||||
/*
|
||||
handle interrupt from pin change for wait_pin()
|
||||
*/
|
||||
static void pal_interrupt_wait(void *arg)
|
||||
{
|
||||
osalSysLockFromISR();
|
||||
struct gpio_entry *g = (gpio_entry *)arg;
|
||||
if (g == nullptr || g->thd_wait == nullptr) {
|
||||
osalSysUnlockFromISR();
|
||||
return;
|
||||
}
|
||||
osalThreadResumeI(&g->thd_wait, MSG_OK);
|
||||
osalSysUnlockFromISR();
|
||||
}
|
||||
|
||||
/*
|
||||
block waiting for a pin to change. A timeout of 0 means wait
|
||||
forever. Return true on pin change, false on timeout
|
||||
*/
|
||||
bool GPIO::wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_us)
|
||||
{
|
||||
struct gpio_entry *g = gpio_by_pin_num(pin);
|
||||
if (!g) {
|
||||
return false;
|
||||
}
|
||||
|
||||
osalSysLock();
|
||||
if (g->thd_wait) {
|
||||
// only allow single waiter
|
||||
osalSysUnlock();
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!_attach_interruptI(g->pal_line,
|
||||
palcallback_t(pal_interrupt_wait),
|
||||
g,
|
||||
mode)) {
|
||||
osalSysUnlock();
|
||||
return false;
|
||||
}
|
||||
|
||||
msg_t msg = osalThreadSuspendTimeoutS(&g->thd_wait, TIME_US2I(timeout_us));
|
||||
_attach_interruptI(g->pal_line,
|
||||
palcallback_t(nullptr),
|
||||
nullptr,
|
||||
mode);
|
||||
osalSysUnlock();
|
||||
|
||||
return msg == MSG_OK;
|
||||
}
|
||||
|
@ -56,11 +56,21 @@ public:
|
||||
/* attach interrupt via ioline_t */
|
||||
bool _attach_interrupt(ioline_t line, AP_HAL::Proc p, uint8_t mode);
|
||||
|
||||
/*
|
||||
block waiting for a pin to change. A timeout of 0 means wait
|
||||
forever. Return true on pin change, false on timeout
|
||||
*/
|
||||
bool wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_us) override;
|
||||
|
||||
private:
|
||||
bool _usb_connected;
|
||||
bool _ext_started;
|
||||
|
||||
bool _attach_interruptI(ioline_t line, palcallback_t cb, void *p, uint8_t mode);
|
||||
bool _attach_interrupt(ioline_t line, palcallback_t cb, void *p, uint8_t mode);
|
||||
#ifdef HAL_PIN_ALT_CONFIG
|
||||
void setup_alt_config(void);
|
||||
#endif
|
||||
};
|
||||
|
||||
class ChibiOS::DigitalSource : public AP_HAL::DigitalSource {
|
||||
|
@ -159,8 +159,6 @@ thread_t* get_main_thread()
|
||||
|
||||
static AP_HAL::HAL::Callbacks* g_callbacks;
|
||||
|
||||
static AP_HAL::Util::PersistentData last_persistent_data;
|
||||
|
||||
static void main_loop()
|
||||
{
|
||||
daemon_task = chThdGetSelfX();
|
||||
@ -200,7 +198,7 @@ static void main_loop()
|
||||
if (stm32_was_watchdog_reset()) {
|
||||
// load saved watchdog data
|
||||
stm32_watchdog_load((uint32_t *)&utilInstance.persistent_data, (sizeof(utilInstance.persistent_data)+3)/4);
|
||||
last_persistent_data = utilInstance.persistent_data;
|
||||
utilInstance.last_persistent_data = utilInstance.persistent_data;
|
||||
}
|
||||
|
||||
schedulerInstance.hal_initialized();
|
||||
@ -217,21 +215,7 @@ static void main_loop()
|
||||
|
||||
#ifndef HAL_NO_LOGGING
|
||||
if (hal.util->was_watchdog_reset()) {
|
||||
AP::internalerror().error(AP_InternalError::error_t::watchdog_reset);
|
||||
const AP_HAL::Util::PersistentData &pd = last_persistent_data;
|
||||
AP::logger().WriteCritical("WDOG", "TimeUS,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine,FL,FT,FA,FP,ICSR", "QbIIHHHHHIBI",
|
||||
AP_HAL::micros64(),
|
||||
pd.scheduler_task,
|
||||
pd.internal_errors,
|
||||
pd.internal_error_count,
|
||||
pd.last_mavlink_msgid,
|
||||
pd.last_mavlink_cmd,
|
||||
pd.semaphore_line,
|
||||
pd.fault_line,
|
||||
pd.fault_type,
|
||||
pd.fault_addr,
|
||||
pd.fault_thd_prio,
|
||||
pd.fault_icsr);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::watchdog_reset);
|
||||
}
|
||||
#endif // HAL_NO_LOGGING
|
||||
#endif // IOMCU_FW
|
||||
@ -279,8 +263,8 @@ void HAL_ChibiOS::run(int argc, char * const argv[], Callbacks* callbacks) const
|
||||
* RTOS is active.
|
||||
*/
|
||||
|
||||
#ifdef HAL_USB_PRODUCT_ID
|
||||
setup_usb_strings();
|
||||
#if HAL_USE_SERIAL_USB == TRUE
|
||||
usb_initialise();
|
||||
#endif
|
||||
|
||||
#ifdef HAL_STDOUT_SERIAL
|
||||
|
@ -126,7 +126,7 @@ I2CDeviceManager::I2CDeviceManager(void)
|
||||
drop the speed to be the minimum speed requested
|
||||
*/
|
||||
businfo[i].busclock = HAL_I2C_MAX_CLOCK;
|
||||
#if defined(STM32F7)
|
||||
#if defined(STM32F7) || defined(STM32F3)
|
||||
if (businfo[i].busclock <= 100000) {
|
||||
businfo[i].i2ccfg.timingr = HAL_I2C_F7_100_TIMINGR;
|
||||
businfo[i].busclock = 100000;
|
||||
@ -166,7 +166,7 @@ I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool u
|
||||
asprintf(&pname, "I2C:%u:%02x",
|
||||
(unsigned)busnum, (unsigned)address);
|
||||
if (bus_clock < bus.busclock) {
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3)
|
||||
if (bus_clock <= 100000) {
|
||||
bus.i2ccfg.timingr = HAL_I2C_F7_100_TIMINGR;
|
||||
bus.busclock = 100000;
|
||||
@ -213,7 +213,7 @@ bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
|
||||
return false;
|
||||
}
|
||||
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3)
|
||||
if (_use_smbus) {
|
||||
bus.i2ccfg.cr1 |= I2C_CR1_SMBHEN;
|
||||
} else {
|
||||
@ -294,7 +294,7 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
|
||||
bus.dma_handle->unlock();
|
||||
|
||||
if (I2CD[bus.busnum].i2c->errors & I2C_ISR_LIMIT) {
|
||||
AP::internalerror().error(AP_InternalError::error_t::i2c_isr);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::i2c_isr);
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -179,6 +179,7 @@ void RCInput::_timer_tick(void)
|
||||
_num_channels = rcprot.num_channels();
|
||||
_num_channels = MIN(_num_channels, RC_INPUT_MAX_CHANNELS);
|
||||
rcprot.read(_rc_values, _num_channels);
|
||||
_rssi = rcprot.get_RSSI();
|
||||
#ifndef HAL_NO_UARTDRIVER
|
||||
rc_protocol = rcprot.protocol_name();
|
||||
#endif
|
||||
@ -206,6 +207,7 @@ void RCInput::_timer_tick(void)
|
||||
_rcin_timestamp_last_signal = last_iomcu_us;
|
||||
#ifndef HAL_NO_UARTDRIVER
|
||||
rc_protocol = iomcu.get_rc_protocol();
|
||||
_rssi = iomcu.get_RSSI();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
@ -214,7 +216,7 @@ void RCInput::_timer_tick(void)
|
||||
#ifndef HAL_NO_UARTDRIVER
|
||||
if (rc_protocol && rc_protocol != last_protocol) {
|
||||
last_protocol = rc_protocol;
|
||||
gcs().send_text(MAV_SEVERITY_DEBUG, "RCInput: decoding %s", last_protocol);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "RCInput: decoding %s", last_protocol);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -63,7 +63,7 @@ private:
|
||||
|
||||
uint64_t _last_read;
|
||||
uint8_t _num_channels;
|
||||
HAL_Semaphore_Recursive rcin_mutex;
|
||||
Semaphore rcin_mutex;
|
||||
int16_t _rssi = -1;
|
||||
uint32_t _rcin_timestamp_last_signal;
|
||||
bool _init;
|
||||
|
@ -208,7 +208,7 @@ bool SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
|
||||
if (msg == MSG_TIMEOUT) {
|
||||
ret = false;
|
||||
if (!hal.scheduler->in_expected_delay()) {
|
||||
AP::internalerror().error(AP_InternalError::error_t::spi_fail);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::spi_fail);
|
||||
}
|
||||
spiAbort(spi_devices[device_desc.bus].driver);
|
||||
}
|
||||
@ -222,7 +222,7 @@ bool SPIDevice::clock_pulse(uint32_t n)
|
||||
{
|
||||
if (!cs_forced) {
|
||||
//special mode to init sdcard without cs asserted
|
||||
bus.semaphore.take(HAL_SEMAPHORE_BLOCK_FOREVER);
|
||||
bus.semaphore.take_blocking();
|
||||
acquire_bus(true, true);
|
||||
spiIgnore(spi_devices[device_desc.bus].driver, n);
|
||||
acquire_bus(false, true);
|
||||
|
@ -307,7 +307,7 @@ void Scheduler::_run_timers()
|
||||
void Scheduler::_timer_thread(void *arg)
|
||||
{
|
||||
Scheduler *sched = (Scheduler *)arg;
|
||||
chRegSetThreadName("apm_timer");
|
||||
chRegSetThreadName("timer");
|
||||
|
||||
while (!sched->_hal_initialized) {
|
||||
sched->delay_microseconds(1000);
|
||||
@ -333,6 +333,10 @@ void Scheduler::_timer_thread(void *arg)
|
||||
*/
|
||||
bool Scheduler::in_expected_delay(void) const
|
||||
{
|
||||
if (!_initialized) {
|
||||
// until setup() is complete we expect delays
|
||||
return true;
|
||||
}
|
||||
if (expect_delay_start != 0) {
|
||||
uint32_t now = AP_HAL::millis();
|
||||
if (now - expect_delay_start <= expect_delay_length) {
|
||||
@ -346,12 +350,15 @@ bool Scheduler::in_expected_delay(void) const
|
||||
void Scheduler::_monitor_thread(void *arg)
|
||||
{
|
||||
Scheduler *sched = (Scheduler *)arg;
|
||||
chRegSetThreadName("apm_monitor");
|
||||
chRegSetThreadName("monitor");
|
||||
|
||||
while (!sched->_initialized) {
|
||||
sched->delay(100);
|
||||
}
|
||||
bool using_watchdog = AP_BoardConfig::watchdog_enabled();
|
||||
#ifndef HAL_NO_LOGGING
|
||||
uint8_t log_wd_counter = 0;
|
||||
#endif
|
||||
|
||||
while (true) {
|
||||
sched->delay(100);
|
||||
@ -364,22 +371,50 @@ void Scheduler::_monitor_thread(void *arg)
|
||||
// the main loop has been stuck for at least
|
||||
// 200ms. Starting logging the main loop state
|
||||
const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
|
||||
AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIIHHHII",
|
||||
AP_HAL::micros64(),
|
||||
loop_delay,
|
||||
pd.scheduler_task,
|
||||
pd.internal_errors,
|
||||
pd.internal_error_count,
|
||||
pd.last_mavlink_msgid,
|
||||
pd.last_mavlink_cmd,
|
||||
pd.semaphore_line,
|
||||
pd.spi_count,
|
||||
pd.i2c_count);
|
||||
if (AP_Logger::get_singleton()) {
|
||||
AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,IErrLn,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIHHHHHII",
|
||||
AP_HAL::micros64(),
|
||||
loop_delay,
|
||||
pd.scheduler_task,
|
||||
pd.internal_errors,
|
||||
pd.internal_error_count,
|
||||
pd.internal_error_last_line,
|
||||
pd.last_mavlink_msgid,
|
||||
pd.last_mavlink_cmd,
|
||||
pd.semaphore_line,
|
||||
pd.spi_count,
|
||||
pd.i2c_count);
|
||||
}
|
||||
}
|
||||
if (loop_delay >= 500) {
|
||||
// at 500ms we declare an internal error
|
||||
AP::internalerror().error(AP_InternalError::error_t::main_loop_stuck);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::main_loop_stuck);
|
||||
}
|
||||
|
||||
#ifndef HAL_NO_LOGGING
|
||||
if (log_wd_counter++ == 10 && hal.util->was_watchdog_reset()) {
|
||||
log_wd_counter = 0;
|
||||
// log watchdog message once a second
|
||||
const AP_HAL::Util::PersistentData &pd = hal.util->last_persistent_data;
|
||||
AP::logger().WriteCritical("WDOG", "TimeUS,Tsk,IE,IEC,IEL,MvMsg,MvCmd,SmLn,FL,FT,FA,FP,ICSR,LR,TN", "QbIHHHHHHHIBIIn",
|
||||
AP_HAL::micros64(),
|
||||
pd.scheduler_task,
|
||||
pd.internal_errors,
|
||||
pd.internal_error_count,
|
||||
pd.internal_error_last_line,
|
||||
pd.last_mavlink_msgid,
|
||||
pd.last_mavlink_cmd,
|
||||
pd.semaphore_line,
|
||||
pd.fault_line,
|
||||
pd.fault_type,
|
||||
pd.fault_addr,
|
||||
pd.fault_thd_prio,
|
||||
pd.fault_icsr,
|
||||
pd.fault_lr,
|
||||
pd.thread_name4);
|
||||
}
|
||||
#endif // HAL_NO_LOGGING
|
||||
|
||||
}
|
||||
}
|
||||
#endif // HAL_NO_MONITOR_THREAD
|
||||
@ -387,7 +422,7 @@ void Scheduler::_monitor_thread(void *arg)
|
||||
void Scheduler::_rcin_thread(void *arg)
|
||||
{
|
||||
Scheduler *sched = (Scheduler *)arg;
|
||||
chRegSetThreadName("apm_rcin");
|
||||
chRegSetThreadName("rcin");
|
||||
while (!sched->_hal_initialized) {
|
||||
sched->delay_microseconds(20000);
|
||||
}
|
||||
@ -421,7 +456,7 @@ void Scheduler::_run_io(void)
|
||||
void Scheduler::_io_thread(void* arg)
|
||||
{
|
||||
Scheduler *sched = (Scheduler *)arg;
|
||||
chRegSetThreadName("apm_io");
|
||||
chRegSetThreadName("io");
|
||||
while (!sched->_hal_initialized) {
|
||||
sched->delay_microseconds(1000);
|
||||
}
|
||||
@ -447,7 +482,7 @@ void Scheduler::_io_thread(void* arg)
|
||||
void Scheduler::_storage_thread(void* arg)
|
||||
{
|
||||
Scheduler *sched = (Scheduler *)arg;
|
||||
chRegSetThreadName("apm_storage");
|
||||
chRegSetThreadName("storage");
|
||||
while (!sched->_hal_initialized) {
|
||||
sched->delay_microseconds(10000);
|
||||
}
|
||||
@ -549,7 +584,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_
|
||||
be used to prevent watchdog reset during expected long delays
|
||||
A value of zero cancels the previous expected delay
|
||||
*/
|
||||
void Scheduler::expect_delay_ms(uint32_t ms)
|
||||
void Scheduler::_expect_delay_ms(uint32_t ms)
|
||||
{
|
||||
if (!in_main_thread()) {
|
||||
// only for main thread
|
||||
@ -559,6 +594,8 @@ void Scheduler::expect_delay_ms(uint32_t ms)
|
||||
// pat once immediately
|
||||
watchdog_pat();
|
||||
|
||||
WITH_SEMAPHORE(expect_delay_sem);
|
||||
|
||||
if (ms == 0) {
|
||||
if (expect_delay_nesting > 0) {
|
||||
expect_delay_nesting--;
|
||||
@ -584,6 +621,18 @@ void Scheduler::expect_delay_ms(uint32_t ms)
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
this is _expect_delay_ms() with check that we are in the main thread
|
||||
*/
|
||||
void Scheduler::expect_delay_ms(uint32_t ms)
|
||||
{
|
||||
if (!in_main_thread()) {
|
||||
// only for main thread
|
||||
return;
|
||||
}
|
||||
_expect_delay_ms(ms);
|
||||
}
|
||||
|
||||
// pat the watchdog
|
||||
void Scheduler::watchdog_pat(void)
|
||||
{
|
||||
|
@ -103,6 +103,7 @@ public:
|
||||
be used to prevent watchdog reset during expected long delays
|
||||
A value of zero cancels the previous expected delay
|
||||
*/
|
||||
void _expect_delay_ms(uint32_t ms);
|
||||
void expect_delay_ms(uint32_t ms) override;
|
||||
|
||||
/*
|
||||
@ -140,6 +141,7 @@ private:
|
||||
uint32_t expect_delay_start;
|
||||
uint32_t expect_delay_length;
|
||||
uint32_t expect_delay_nesting;
|
||||
HAL_Semaphore expect_delay_sem;
|
||||
|
||||
AP_HAL::MemberProc _timer_proc[CHIBIOS_SCHEDULER_MAX_TIMER_PROCS];
|
||||
uint8_t _num_timer_procs;
|
||||
|
@ -76,77 +76,4 @@ void Semaphore::assert_owner(void)
|
||||
osalDbgAssert(check_owner(), "owner");
|
||||
}
|
||||
|
||||
// constructor
|
||||
Semaphore_Recursive::Semaphore_Recursive()
|
||||
: Semaphore(), count(0)
|
||||
{}
|
||||
|
||||
|
||||
bool Semaphore_Recursive::give()
|
||||
{
|
||||
chSysLock();
|
||||
mutex_t *mtx = (mutex_t *)_lock;
|
||||
osalDbgAssert(count>0, "recursive semaphore");
|
||||
if (count != 0) {
|
||||
count--;
|
||||
if (count == 0) {
|
||||
// this thread is giving it up
|
||||
chMtxUnlockS(mtx);
|
||||
// we may need to re-schedule if our priority was increased due to
|
||||
// priority inheritance
|
||||
chSchRescheduleS();
|
||||
}
|
||||
}
|
||||
chSysUnlock();
|
||||
return true;
|
||||
}
|
||||
|
||||
bool Semaphore_Recursive::take(uint32_t timeout_ms)
|
||||
{
|
||||
// most common case is we can get the lock immediately
|
||||
if (Semaphore::take_nonblocking()) {
|
||||
count=1;
|
||||
return true;
|
||||
}
|
||||
|
||||
// check for case where we hold it already
|
||||
chSysLock();
|
||||
mutex_t *mtx = (mutex_t *)_lock;
|
||||
if (mtx->owner == chThdGetSelfX()) {
|
||||
count++;
|
||||
chSysUnlock();
|
||||
return true;
|
||||
}
|
||||
chSysUnlock();
|
||||
if (Semaphore::take(timeout_ms)) {
|
||||
count = 1;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool Semaphore_Recursive::take_nonblocking(void)
|
||||
{
|
||||
// most common case is we can get the lock immediately
|
||||
if (Semaphore::take_nonblocking()) {
|
||||
count=1;
|
||||
return true;
|
||||
}
|
||||
|
||||
// check for case where we hold it already
|
||||
chSysLock();
|
||||
mutex_t *mtx = (mutex_t *)_lock;
|
||||
if (mtx->owner == chThdGetSelfX()) {
|
||||
count++;
|
||||
chSysUnlock();
|
||||
return true;
|
||||
}
|
||||
chSysUnlock();
|
||||
if (Semaphore::take_nonblocking()) {
|
||||
count = 1;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // CH_CFG_USE_MUTEXES
|
||||
|
@ -34,18 +34,6 @@ public:
|
||||
void assert_owner(void);
|
||||
protected:
|
||||
// to avoid polluting the global namespace with the 'ch' variable,
|
||||
// we declare the lock as a uint64_t, and cast inside the cpp file
|
||||
uint64_t _lock[2];
|
||||
};
|
||||
|
||||
// a recursive semaphore, allowing for a thread to take it more than
|
||||
// once. It must be released the same number of times it is taken
|
||||
class ChibiOS::Semaphore_Recursive : public ChibiOS::Semaphore {
|
||||
public:
|
||||
Semaphore_Recursive();
|
||||
bool give() override;
|
||||
bool take(uint32_t timeout_ms) override;
|
||||
bool take_nonblocking() override;
|
||||
private:
|
||||
uint32_t count;
|
||||
// we declare the lock as a uint32_t array, and cast inside the cpp file
|
||||
uint32_t _lock[5];
|
||||
};
|
||||
|
@ -340,9 +340,19 @@ bool Storage::_flash_erase_sector(uint8_t sector)
|
||||
// erasing a page can take long enough that USB may not initialise properly if it happens
|
||||
// while the host is connecting. Only do a flash erase if we have been up for more than 4s
|
||||
for (uint8_t i=0; i<STORAGE_FLASH_RETRIES; i++) {
|
||||
/*
|
||||
a sector erase stops the whole MCU. We need to setup a long
|
||||
expected delay, and not only when running in the main
|
||||
thread. We can't use EXPECT_DELAY_MS() as it checks we are
|
||||
in the main thread
|
||||
*/
|
||||
ChibiOS::Scheduler *sched = (ChibiOS::Scheduler *)hal.scheduler;
|
||||
sched->_expect_delay_ms(1000);
|
||||
if (hal.flash->erasepage(_flash_page+sector)) {
|
||||
sched->_expect_delay_ms(0);
|
||||
return true;
|
||||
}
|
||||
sched->_expect_delay_ms(0);
|
||||
hal.scheduler->delay(1);
|
||||
}
|
||||
return false;
|
||||
|
@ -48,10 +48,13 @@ UARTDriver *UARTDriver::uart_drivers[UART_MAX_DRIVERS];
|
||||
|
||||
// event used to wake up waiting thread. This event number is for
|
||||
// caller threads
|
||||
#define EVT_DATA EVENT_MASK(0)
|
||||
#define EVT_DATA EVENT_MASK(10)
|
||||
|
||||
// event for parity error
|
||||
#define EVT_PARITY EVENT_MASK(1)
|
||||
#define EVT_PARITY EVENT_MASK(11)
|
||||
|
||||
// event for transmit end for half-duplex
|
||||
#define EVT_TRANSMIT_END EVENT_MASK(12)
|
||||
|
||||
#ifndef HAL_UART_MIN_TX_SIZE
|
||||
#define HAL_UART_MIN_TX_SIZE 1024
|
||||
@ -98,8 +101,9 @@ void UARTDriver::uart_thread(void* arg)
|
||||
if (uart_drivers[i] == nullptr) {
|
||||
continue;
|
||||
}
|
||||
if ((mask & EVENT_MASK(i)) &&
|
||||
uart_drivers[i]->_initialised) {
|
||||
if (uart_drivers[i]->_initialised &&
|
||||
(mask & EVENT_MASK(i) ||
|
||||
(uart_drivers[i]->hd_tx_active && (mask & EVT_TRANSMIT_END)))) {
|
||||
uart_drivers[i]->_timer_tick();
|
||||
}
|
||||
}
|
||||
@ -209,14 +213,25 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
}
|
||||
|
||||
#ifndef HAL_UART_NODMA
|
||||
if (rx_bounce_buf == nullptr) {
|
||||
rx_bounce_buf = (uint8_t *)hal.util->malloc_type(RX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
|
||||
if (!half_duplex && !(_last_options & OPTION_NODMA_RX)) {
|
||||
if (rx_bounce_buf[0] == nullptr && sdef.dma_rx) {
|
||||
rx_bounce_buf[0] = (uint8_t *)hal.util->malloc_type(RX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
|
||||
}
|
||||
if (rx_bounce_buf[1] == nullptr && sdef.dma_rx) {
|
||||
rx_bounce_buf[1] = (uint8_t *)hal.util->malloc_type(RX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
|
||||
}
|
||||
}
|
||||
if (tx_bounce_buf == nullptr) {
|
||||
if (tx_bounce_buf == nullptr && sdef.dma_tx && !(_last_options & OPTION_NODMA_TX)) {
|
||||
tx_bounce_buf = (uint8_t *)hal.util->malloc_type(TX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
|
||||
chVTObjectInit(&tx_timeout);
|
||||
tx_bounce_buf_ready = true;
|
||||
}
|
||||
if (half_duplex) {
|
||||
rx_dma_enabled = tx_dma_enabled = false;
|
||||
} else {
|
||||
rx_dma_enabled = rx_bounce_buf[0] != nullptr && rx_bounce_buf[1] != nullptr;
|
||||
tx_dma_enabled = tx_bounce_buf != nullptr;
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
@ -241,21 +256,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
*/
|
||||
if (!_device_initialised) {
|
||||
if ((SerialUSBDriver*)sdef.serial == &SDU1) {
|
||||
sduObjectInit(&SDU1);
|
||||
sduStart(&SDU1, &serusbcfg1);
|
||||
#if HAL_HAVE_DUAL_USB_CDC
|
||||
sduObjectInit(&SDU2);
|
||||
sduStart(&SDU2, &serusbcfg2);
|
||||
#endif
|
||||
/*
|
||||
* Activates the USB driver and then the USB bus pull-up on D+.
|
||||
* Note, a delay is inserted in order to not have to disconnect the cable
|
||||
* after a reset.
|
||||
*/
|
||||
usbDisconnectBus(serusbcfg1.usbp);
|
||||
hal.scheduler->delay_microseconds(1500);
|
||||
usbStart(serusbcfg1.usbp, &usbcfg);
|
||||
usbConnectBus(serusbcfg1.usbp);
|
||||
usb_initialise();
|
||||
}
|
||||
_device_initialised = true;
|
||||
}
|
||||
@ -265,9 +266,9 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
if (_baudrate != 0) {
|
||||
#ifndef HAL_UART_NODMA
|
||||
bool was_initialised = _device_initialised;
|
||||
//setup Rx DMA
|
||||
if(!_device_initialised) {
|
||||
if(sdef.dma_rx) {
|
||||
// setup Rx DMA
|
||||
if (!_device_initialised) {
|
||||
if (rx_dma_enabled) {
|
||||
osalDbgAssert(rxdma == nullptr, "double DMA allocation");
|
||||
chSysLock();
|
||||
rxdma = dmaStreamAllocI(sdef.dma_rx_stream_id,
|
||||
@ -276,7 +277,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
(void *)this);
|
||||
osalDbgAssert(rxdma, "stream alloc failed");
|
||||
chSysUnlock();
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3)
|
||||
dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->RDR);
|
||||
#else
|
||||
dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->DR);
|
||||
@ -285,7 +286,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
dmaSetRequestSource(rxdma, sdef.dma_rx_channel_id);
|
||||
#endif
|
||||
}
|
||||
if (sdef.dma_tx) {
|
||||
if (tx_dma_enabled) {
|
||||
// we only allow for sharing of the TX DMA channel, not the RX
|
||||
// DMA channel, as the RX side is active all the time, so
|
||||
// cannot be shared
|
||||
@ -300,20 +301,17 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
sercfg.speed = _baudrate;
|
||||
|
||||
// start with options from set_options()
|
||||
sercfg.cr1 = 0;
|
||||
sercfg.cr1 = _cr1_options;
|
||||
sercfg.cr2 = _cr2_options;
|
||||
sercfg.cr3 = _cr3_options;
|
||||
|
||||
#ifndef HAL_UART_NODMA
|
||||
if (!sdef.dma_tx && !sdef.dma_rx) {
|
||||
} else {
|
||||
if (sdef.dma_rx) {
|
||||
sercfg.cr1 |= USART_CR1_IDLEIE;
|
||||
sercfg.cr3 |= USART_CR3_DMAR;
|
||||
}
|
||||
if (sdef.dma_tx) {
|
||||
sercfg.cr3 |= USART_CR3_DMAT;
|
||||
}
|
||||
if (rx_dma_enabled) {
|
||||
sercfg.cr1 |= USART_CR1_IDLEIE;
|
||||
sercfg.cr3 |= USART_CR3_DMAR;
|
||||
}
|
||||
if (tx_dma_enabled) {
|
||||
sercfg.cr3 |= USART_CR3_DMAT;
|
||||
}
|
||||
sercfg.irq_cb = rx_irq_cb;
|
||||
#endif // HAL_UART_NODMA
|
||||
@ -323,20 +321,14 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
sdStart((SerialDriver*)sdef.serial, &sercfg);
|
||||
|
||||
#ifndef HAL_UART_NODMA
|
||||
if(sdef.dma_rx) {
|
||||
if (rx_dma_enabled) {
|
||||
//Configure serial driver to skip handling RX packets
|
||||
//because we will handle them via DMA
|
||||
((SerialDriver*)sdef.serial)->usart->CR1 &= ~USART_CR1_RXNEIE;
|
||||
//Start DMA
|
||||
if(!was_initialised) {
|
||||
uint32_t dmamode = STM32_DMA_CR_DMEIE | STM32_DMA_CR_TEIE;
|
||||
dmamode |= STM32_DMA_CR_CHSEL(sdef.dma_rx_channel_id);
|
||||
dmamode |= STM32_DMA_CR_PL(0);
|
||||
dmaStreamSetMemory0(rxdma, rx_bounce_buf);
|
||||
dmaStreamSetTransactionSize(rxdma, RX_BOUNCE_BUFSIZE);
|
||||
dmaStreamSetMode(rxdma, dmamode | STM32_DMA_CR_DIR_P2M |
|
||||
STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
|
||||
dmaStreamEnable(rxdma);
|
||||
// Start DMA
|
||||
if (!was_initialised) {
|
||||
dmaStreamDisable(rxdma);
|
||||
dma_rx_enable();
|
||||
}
|
||||
}
|
||||
#endif // HAL_UART_NODMA
|
||||
@ -374,7 +366,7 @@ void UARTDriver::dma_tx_allocate(Shared_DMA *ctx)
|
||||
(void *)this);
|
||||
osalDbgAssert(txdma, "stream alloc failed");
|
||||
chSysUnlock();
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3)
|
||||
dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->TDR);
|
||||
#else
|
||||
dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->DR);
|
||||
@ -385,6 +377,21 @@ void UARTDriver::dma_tx_allocate(Shared_DMA *ctx)
|
||||
#endif // HAL_USE_SERIAL
|
||||
}
|
||||
|
||||
#ifndef HAL_UART_NODMA
|
||||
void UARTDriver::dma_rx_enable(void)
|
||||
{
|
||||
uint32_t dmamode = STM32_DMA_CR_DMEIE | STM32_DMA_CR_TEIE;
|
||||
dmamode |= STM32_DMA_CR_CHSEL(sdef.dma_rx_channel_id);
|
||||
dmamode |= STM32_DMA_CR_PL(0);
|
||||
rx_bounce_idx ^= 1;
|
||||
dmaStreamSetMemory0(rxdma, rx_bounce_buf[rx_bounce_idx]);
|
||||
dmaStreamSetTransactionSize(rxdma, RX_BOUNCE_BUFSIZE);
|
||||
dmaStreamSetMode(rxdma, dmamode | STM32_DMA_CR_DIR_P2M |
|
||||
STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
|
||||
dmaStreamEnable(rxdma);
|
||||
}
|
||||
#endif
|
||||
|
||||
void UARTDriver::dma_tx_deallocate(Shared_DMA *ctx)
|
||||
{
|
||||
chSysLock();
|
||||
@ -394,7 +401,7 @@ void UARTDriver::dma_tx_deallocate(Shared_DMA *ctx)
|
||||
}
|
||||
|
||||
/*
|
||||
DMA transmit complettion interrupt handler
|
||||
DMA transmit completion interrupt handler
|
||||
*/
|
||||
void UARTDriver::tx_complete(void* self, uint32_t flags)
|
||||
{
|
||||
@ -416,16 +423,21 @@ void UARTDriver::tx_complete(void* self, uint32_t flags)
|
||||
}
|
||||
|
||||
|
||||
#ifndef HAL_UART_NODMA
|
||||
void UARTDriver::rx_irq_cb(void* self)
|
||||
{
|
||||
#if HAL_USE_SERIAL == TRUE
|
||||
UARTDriver* uart_drv = (UARTDriver*)self;
|
||||
if (!uart_drv->sdef.dma_rx) {
|
||||
if (!uart_drv->rx_dma_enabled) {
|
||||
return;
|
||||
}
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
//disable dma, triggering DMA transfer complete interrupt
|
||||
uart_drv->rxdma->stream->CR &= ~STM32_DMA_CR_EN;
|
||||
#elif defined(STM32F3)
|
||||
//disable dma, triggering DMA transfer complete interrupt
|
||||
dmaStreamDisable(uart_drv->rxdma);
|
||||
uart_drv->rxdma->channel->CCR &= ~STM32_DMA_CR_EN;
|
||||
#else
|
||||
volatile uint16_t sr = ((SerialDriver*)(uart_drv->sdef.serial))->usart->SR;
|
||||
if(sr & USART_SR_IDLE) {
|
||||
@ -437,37 +449,37 @@ void UARTDriver::rx_irq_cb(void* self)
|
||||
#endif // STM32F7
|
||||
#endif // HAL_USE_SERIAL
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
handle a RX DMA full interrupt
|
||||
*/
|
||||
void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags)
|
||||
{
|
||||
#if HAL_USE_SERIAL == TRUE
|
||||
UARTDriver* uart_drv = (UARTDriver*)self;
|
||||
if (uart_drv->_lock_rx_in_timer_tick) {
|
||||
if (!uart_drv->rx_dma_enabled) {
|
||||
return;
|
||||
}
|
||||
if (!uart_drv->sdef.dma_rx) {
|
||||
return;
|
||||
}
|
||||
stm32_cacheBufferInvalidate(uart_drv->rx_bounce_buf, RX_BOUNCE_BUFSIZE);
|
||||
uint8_t len = RX_BOUNCE_BUFSIZE - dmaStreamGetTransactionSize(uart_drv->rxdma);
|
||||
uint16_t len = RX_BOUNCE_BUFSIZE - dmaStreamGetTransactionSize(uart_drv->rxdma);
|
||||
const uint8_t bounce_idx = uart_drv->rx_bounce_idx;
|
||||
|
||||
// restart the DMA transfers immediately. This switches to the
|
||||
// other bounce buffer. We restart the DMA before we copy the data
|
||||
// out to minimise the time with DMA disabled, which allows us to
|
||||
// handle much higher receiver baudrates
|
||||
dmaStreamDisable(uart_drv->rxdma);
|
||||
uart_drv->dma_rx_enable();
|
||||
|
||||
if (len > 0) {
|
||||
if (uart_drv->half_duplex) {
|
||||
uint32_t now = AP_HAL::micros();
|
||||
if (now - uart_drv->hd_write_us < uart_drv->hd_read_delay_us) {
|
||||
len = 0;
|
||||
}
|
||||
}
|
||||
|
||||
stm32_cacheBufferInvalidate(uart_drv->rx_bounce_buf, len);
|
||||
uart_drv->_readbuf.write(uart_drv->rx_bounce_buf, len);
|
||||
|
||||
/*
|
||||
we have data to copy out
|
||||
*/
|
||||
stm32_cacheBufferInvalidate(uart_drv->rx_bounce_buf[bounce_idx], len);
|
||||
uart_drv->_readbuf.write(uart_drv->rx_bounce_buf[bounce_idx], len);
|
||||
uart_drv->receive_timestamp_update();
|
||||
}
|
||||
|
||||
//restart the DMA transfers
|
||||
dmaStreamSetMemory0(uart_drv->rxdma, uart_drv->rx_bounce_buf);
|
||||
dmaStreamSetTransactionSize(uart_drv->rxdma, RX_BOUNCE_BUFSIZE);
|
||||
dmaStreamEnable(uart_drv->rxdma);
|
||||
if (uart_drv->_wait.thread_ctx && uart_drv->_readbuf.available() >= uart_drv->_wait.n) {
|
||||
chSysLockFromISR();
|
||||
chEvtSignalI(uart_drv->_wait.thread_ctx, EVT_DATA);
|
||||
@ -590,12 +602,13 @@ int16_t UARTDriver::read_locked(uint32_t key)
|
||||
return byte;
|
||||
}
|
||||
|
||||
/* Empty implementations of Print virtual methods */
|
||||
/* write one byte to the port */
|
||||
size_t UARTDriver::write(uint8_t c)
|
||||
{
|
||||
if (lock_write_key != 0 || !_write_mutex.take_nonblocking()) {
|
||||
if (lock_write_key != 0) {
|
||||
return 0;
|
||||
}
|
||||
_write_mutex.take_blocking();
|
||||
|
||||
if (!_initialised) {
|
||||
_write_mutex.give();
|
||||
@ -607,7 +620,10 @@ size_t UARTDriver::write(uint8_t c)
|
||||
_write_mutex.give();
|
||||
return 0;
|
||||
}
|
||||
// release the semaphore while sleeping
|
||||
_write_mutex.give();
|
||||
hal.scheduler->delay(1);
|
||||
_write_mutex.take_blocking();
|
||||
}
|
||||
size_t ret = _writebuf.write(&c, 1);
|
||||
if (unbuffered_writes) {
|
||||
@ -617,25 +633,17 @@ size_t UARTDriver::write(uint8_t c)
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* write a block of bytes to the port */
|
||||
size_t UARTDriver::write(const uint8_t *buffer, size_t size)
|
||||
{
|
||||
if (!_initialised || lock_write_key != 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (_blocking_writes && unbuffered_writes) {
|
||||
_write_mutex.take_blocking();
|
||||
} else {
|
||||
if (!_write_mutex.take_nonblocking()) {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
if (_blocking_writes && !unbuffered_writes) {
|
||||
/*
|
||||
use the per-byte delay loop in write() above for blocking writes
|
||||
*/
|
||||
_write_mutex.give();
|
||||
size_t ret = 0;
|
||||
while (size--) {
|
||||
if (write(*buffer++) != 1) break;
|
||||
@ -644,11 +652,12 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
|
||||
return ret;
|
||||
}
|
||||
|
||||
WITH_SEMAPHORE(_write_mutex);
|
||||
|
||||
size_t ret = _writebuf.write(buffer, size);
|
||||
if (unbuffered_writes) {
|
||||
write_pending_bytes();
|
||||
}
|
||||
_write_mutex.give();
|
||||
return ret;
|
||||
}
|
||||
|
||||
@ -679,14 +688,8 @@ size_t UARTDriver::write_locked(const uint8_t *buffer, size_t size, uint32_t key
|
||||
if (lock_write_key != 0 && key != lock_write_key) {
|
||||
return 0;
|
||||
}
|
||||
if (!_write_mutex.take_nonblocking()) {
|
||||
return 0;
|
||||
}
|
||||
size_t ret = _writebuf.write(buffer, size);
|
||||
|
||||
_write_mutex.give();
|
||||
|
||||
return ret;
|
||||
WITH_SEMAPHORE(_write_mutex);
|
||||
return _writebuf.write(buffer, size);
|
||||
}
|
||||
|
||||
/*
|
||||
@ -717,7 +720,12 @@ void UARTDriver::check_dma_tx_completion(void)
|
||||
{
|
||||
chSysLock();
|
||||
if (!tx_bounce_buf_ready) {
|
||||
if (!(txdma->stream->CR & STM32_DMA_CR_EN)) {
|
||||
#if defined(STM32F3)
|
||||
bool enabled = (txdma->channel->CCR & STM32_DMA_CR_EN);
|
||||
#else
|
||||
bool enabled = (txdma->stream->CR & STM32_DMA_CR_EN);
|
||||
#endif
|
||||
if (!enabled) {
|
||||
if (dmaStreamGetTransactionSize(txdma) == 0) {
|
||||
tx_bounce_buf_ready = true;
|
||||
_last_write_completed_us = AP_HAL::micros();
|
||||
@ -751,6 +759,7 @@ void UARTDriver::handle_tx_timeout(void *arg)
|
||||
*/
|
||||
void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
||||
{
|
||||
WITH_SEMAPHORE(_write_mutex);
|
||||
check_dma_tx_completion();
|
||||
|
||||
if (!tx_bounce_buf_ready) {
|
||||
@ -781,10 +790,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
||||
}
|
||||
}
|
||||
|
||||
if (half_duplex) {
|
||||
half_duplex_setup_delay(tx_len);
|
||||
}
|
||||
|
||||
dmaStreamDisable(txdma);
|
||||
tx_bounce_buf_ready = false;
|
||||
osalDbgAssert(txdma != nullptr, "UART TX DMA allocation failed");
|
||||
stm32_cacheBufferFlush(tx_bounce_buf, tx_len);
|
||||
@ -806,9 +812,15 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
||||
*/
|
||||
void UARTDriver::write_pending_bytes_NODMA(uint32_t n)
|
||||
{
|
||||
WITH_SEMAPHORE(_write_mutex);
|
||||
|
||||
ByteBuffer::IoVec vec[2];
|
||||
uint16_t nwritten = 0;
|
||||
|
||||
if (half_duplex && n > 1) {
|
||||
half_duplex_setup_tx();
|
||||
}
|
||||
|
||||
const auto n_vec = _writebuf.peekiovec(vec, n);
|
||||
for (int i = 0; i < n_vec; i++) {
|
||||
int ret = -1;
|
||||
@ -838,10 +850,6 @@ void UARTDriver::write_pending_bytes_NODMA(uint32_t n)
|
||||
}
|
||||
|
||||
_total_written += nwritten;
|
||||
|
||||
if (half_duplex) {
|
||||
half_duplex_setup_delay(nwritten);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
@ -852,7 +860,7 @@ void UARTDriver::write_pending_bytes(void)
|
||||
uint32_t n;
|
||||
|
||||
#ifndef HAL_UART_NODMA
|
||||
if (sdef.dma_tx) {
|
||||
if (tx_dma_enabled) {
|
||||
check_dma_tx_completion();
|
||||
}
|
||||
#endif
|
||||
@ -864,7 +872,7 @@ void UARTDriver::write_pending_bytes(void)
|
||||
}
|
||||
|
||||
#ifndef HAL_UART_NODMA
|
||||
if (sdef.dma_tx) {
|
||||
if (tx_dma_enabled) {
|
||||
write_pending_bytes_DMA(n);
|
||||
} else
|
||||
#endif
|
||||
@ -878,7 +886,7 @@ void UARTDriver::write_pending_bytes(void)
|
||||
_first_write_started_us = AP_HAL::micros();
|
||||
}
|
||||
#ifndef HAL_UART_NODMA
|
||||
if (sdef.dma_tx) {
|
||||
if (tx_dma_enabled) {
|
||||
// when we are using DMA we have a reliable indication that a write
|
||||
// has completed from the DMA completion interrupt
|
||||
if (_last_write_completed_us != 0) {
|
||||
@ -909,15 +917,24 @@ void UARTDriver::write_pending_bytes(void)
|
||||
}
|
||||
|
||||
/*
|
||||
setup a delay after writing bytes to a half duplex UART to prevent
|
||||
read-back of the same bytes that we wrote. half-duplex protocols
|
||||
tend to have quite loose timing, which makes this possible
|
||||
setup for half duplex tramsmit. To cope with uarts that have level
|
||||
shifters and pullups we need to play a trick where we temporarily
|
||||
disable half-duplex while transmitting. That disables the receive
|
||||
part of the uart on the pin which allows the transmit side to
|
||||
correctly setup the idle voltage before the transmit starts.
|
||||
*/
|
||||
void UARTDriver::half_duplex_setup_delay(uint16_t len)
|
||||
void UARTDriver::half_duplex_setup_tx(void)
|
||||
{
|
||||
const uint16_t pad_us = 1000;
|
||||
hd_write_us = AP_HAL::micros();
|
||||
hd_read_delay_us = ((1000000UL * len * 10) / _baudrate) + pad_us;
|
||||
#ifdef HAVE_USB_SERIAL
|
||||
if (!hd_tx_active) {
|
||||
chEvtGetAndClearFlags(&hd_listener);
|
||||
hd_tx_active = true;
|
||||
SerialDriver *sd = (SerialDriver*)(sdef.serial);
|
||||
sdStop(sd);
|
||||
sercfg.cr3 &= ~USART_CR3_HDSEL;
|
||||
sdStart(sd, &sercfg);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@ -930,30 +947,48 @@ void UARTDriver::_timer_tick(void)
|
||||
{
|
||||
if (!_initialised) return;
|
||||
|
||||
#ifdef HAVE_USB_SERIAL
|
||||
if (hd_tx_active && (chEvtGetAndClearFlags(&hd_listener) & CHN_OUTPUT_EMPTY) != 0) {
|
||||
/*
|
||||
half-duplex transmit has finished. We now re-enable the
|
||||
HDSEL bit for receive
|
||||
*/
|
||||
SerialDriver *sd = (SerialDriver*)(sdef.serial);
|
||||
sdStop(sd);
|
||||
sercfg.cr3 |= USART_CR3_HDSEL;
|
||||
sdStart(sd, &sercfg);
|
||||
hd_tx_active = false;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifndef HAL_UART_NODMA
|
||||
if (sdef.dma_rx && rxdma) {
|
||||
_lock_rx_in_timer_tick = true;
|
||||
if (rx_dma_enabled && rxdma) {
|
||||
chSysLock();
|
||||
//Check if DMA is enabled
|
||||
//if not, it might be because the DMA interrupt was silenced
|
||||
//let's handle that here so that we can continue receiving
|
||||
if (!(rxdma->stream->CR & STM32_DMA_CR_EN)) {
|
||||
#if defined(STM32F3)
|
||||
bool enabled = (rxdma->channel->CCR & STM32_DMA_CR_EN);
|
||||
#else
|
||||
bool enabled = (rxdma->stream->CR & STM32_DMA_CR_EN);
|
||||
#endif
|
||||
if (!enabled) {
|
||||
uint8_t len = RX_BOUNCE_BUFSIZE - dmaStreamGetTransactionSize(rxdma);
|
||||
if (len != 0) {
|
||||
stm32_cacheBufferInvalidate(rx_bounce_buf, len);
|
||||
_readbuf.write(rx_bounce_buf, len);
|
||||
stm32_cacheBufferInvalidate(rx_bounce_buf[rx_bounce_idx], len);
|
||||
_readbuf.write(rx_bounce_buf[rx_bounce_idx], len);
|
||||
|
||||
receive_timestamp_update();
|
||||
if (_rts_is_active) {
|
||||
update_rts_line();
|
||||
}
|
||||
}
|
||||
//DMA disabled by idle interrupt never got a chance to be handled
|
||||
//we will enable it here
|
||||
dmaStreamSetMemory0(rxdma, rx_bounce_buf);
|
||||
dmaStreamSetTransactionSize(rxdma, RX_BOUNCE_BUFSIZE);
|
||||
dmaStreamEnable(rxdma);
|
||||
// DMA disabled by idle interrupt never got a chance to be handled
|
||||
// we will enable it here
|
||||
dmaStreamDisable(rxdma);
|
||||
dma_rx_enable();
|
||||
}
|
||||
_lock_rx_in_timer_tick = false;
|
||||
chSysUnlock();
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -973,7 +1008,7 @@ void UARTDriver::_timer_tick(void)
|
||||
_in_timer = true;
|
||||
|
||||
#ifndef HAL_UART_NODMA
|
||||
if (!sdef.dma_rx)
|
||||
if (!rx_dma_enabled)
|
||||
#endif
|
||||
{
|
||||
// try to fill the read buffer
|
||||
@ -1001,15 +1036,10 @@ void UARTDriver::_timer_tick(void)
|
||||
ret = -1;
|
||||
}
|
||||
#endif
|
||||
if (half_duplex) {
|
||||
uint32_t now = AP_HAL::micros();
|
||||
if (now - hd_write_us < hd_read_delay_us) {
|
||||
break;
|
||||
}
|
||||
if (!hd_tx_active) {
|
||||
_readbuf.commit((unsigned)ret);
|
||||
receive_timestamp_update();
|
||||
}
|
||||
_readbuf.commit((unsigned)ret);
|
||||
|
||||
receive_timestamp_update();
|
||||
|
||||
/* stop reading as we read less than we asked for */
|
||||
if ((unsigned)ret < vec[i].len) {
|
||||
@ -1026,9 +1056,8 @@ 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
|
||||
_write_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER);
|
||||
WITH_SEMAPHORE(_write_mutex);
|
||||
write_pending_bytes();
|
||||
_write_mutex.give();
|
||||
} else {
|
||||
write_pending_bytes();
|
||||
}
|
||||
@ -1120,16 +1149,8 @@ void UARTDriver::update_rts_line(void)
|
||||
*/
|
||||
bool UARTDriver::set_unbuffered_writes(bool on)
|
||||
{
|
||||
#ifdef HAL_UART_NODMA
|
||||
return false;
|
||||
#else
|
||||
if (on && !sdef.dma_tx) {
|
||||
// we can't implement low latemcy writes safely without TX DMA
|
||||
return false;
|
||||
}
|
||||
unbuffered_writes = on;
|
||||
return true;
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
@ -1146,7 +1167,7 @@ void UARTDriver::configure_parity(uint8_t v)
|
||||
sdStop((SerialDriver*)sdef.serial);
|
||||
|
||||
#ifdef USART_CR1_M0
|
||||
// cope with F7 where there are 2 bits in CR1_M
|
||||
// cope with F3 and F7 where there are 2 bits in CR1_M
|
||||
const uint32_t cr1_m0 = USART_CR1_M0;
|
||||
#else
|
||||
const uint32_t cr1_m0 = USART_CR1_M;
|
||||
@ -1187,9 +1208,9 @@ void UARTDriver::configure_parity(uint8_t v)
|
||||
#endif
|
||||
|
||||
#ifndef HAL_UART_NODMA
|
||||
if(sdef.dma_rx) {
|
||||
//Configure serial driver to skip handling RX packets
|
||||
//because we will handle them via DMA
|
||||
if (rx_dma_enabled) {
|
||||
// Configure serial driver to skip handling RX packets
|
||||
// because we will handle them via DMA
|
||||
((SerialDriver*)sdef.serial)->usart->CR1 &= ~USART_CR1_RXNEIE;
|
||||
}
|
||||
#endif
|
||||
@ -1220,7 +1241,7 @@ void UARTDriver::set_stop_bits(int n)
|
||||
|
||||
sdStart((SerialDriver*)sdef.serial, &sercfg);
|
||||
#ifndef HAL_UART_NODMA
|
||||
if(sdef.dma_rx) {
|
||||
if (rx_dma_enabled) {
|
||||
//Configure serial driver to skip handling RX packets
|
||||
//because we will handle them via DMA
|
||||
((SerialDriver*)sdef.serial)->usart->CR1 &= ~USART_CR1_RXNEIE;
|
||||
@ -1261,8 +1282,29 @@ uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)
|
||||
return last_receive_us;
|
||||
}
|
||||
|
||||
/*
|
||||
set user specified PULLUP/PULLDOWN options from SERIALn_OPTIONS
|
||||
*/
|
||||
void UARTDriver::set_pushpull(uint16_t options)
|
||||
{
|
||||
#if HAL_USE_SERIAL == TRUE && !defined(STM32F1)
|
||||
if ((options & OPTION_PULLDOWN_RX) && sdef.rx_line) {
|
||||
palLineSetPushPull(sdef.rx_line, PAL_PUSHPULL_PULLDOWN);
|
||||
}
|
||||
if ((options & OPTION_PULLDOWN_TX) && sdef.tx_line) {
|
||||
palLineSetPushPull(sdef.tx_line, PAL_PUSHPULL_PULLDOWN);
|
||||
}
|
||||
if ((options & OPTION_PULLUP_RX) && sdef.rx_line) {
|
||||
palLineSetPushPull(sdef.rx_line, PAL_PUSHPULL_PULLUP);
|
||||
}
|
||||
if ((options & OPTION_PULLUP_TX) && sdef.tx_line) {
|
||||
palLineSetPushPull(sdef.tx_line, PAL_PUSHPULL_PULLUP);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// set optional features, return true on success
|
||||
bool UARTDriver::set_options(uint8_t options)
|
||||
bool UARTDriver::set_options(uint16_t options)
|
||||
{
|
||||
if (sdef.is_usb) {
|
||||
// no options allowed on USB
|
||||
@ -1278,19 +1320,33 @@ bool UARTDriver::set_options(uint8_t options)
|
||||
uint32_t cr3 = sd->usart->CR3;
|
||||
bool was_enabled = (sd->usart->CR1 & USART_CR1_UE);
|
||||
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F3)
|
||||
// F7 has built-in support for inversion in all uarts
|
||||
ioline_t rx_line = (options & OPTION_SWAP)?sdef.tx_line:sdef.rx_line;
|
||||
ioline_t tx_line = (options & OPTION_SWAP)?sdef.rx_line:sdef.tx_line;
|
||||
if (options & OPTION_RXINV) {
|
||||
cr2 |= USART_CR2_RXINV;
|
||||
_cr2_options |= USART_CR2_RXINV;
|
||||
if (rx_line != 0) {
|
||||
palLineSetPushPull(rx_line, PAL_PUSHPULL_PULLDOWN);
|
||||
}
|
||||
} else {
|
||||
cr2 &= ~USART_CR2_RXINV;
|
||||
if (rx_line != 0) {
|
||||
palLineSetPushPull(rx_line, PAL_PUSHPULL_PULLUP);
|
||||
}
|
||||
}
|
||||
if (options & OPTION_TXINV) {
|
||||
cr2 |= USART_CR2_TXINV;
|
||||
_cr2_options |= USART_CR2_TXINV;
|
||||
if (tx_line != 0) {
|
||||
palLineSetPushPull(tx_line, PAL_PUSHPULL_PULLDOWN);
|
||||
}
|
||||
} else {
|
||||
cr2 &= ~USART_CR2_TXINV;
|
||||
if (tx_line != 0) {
|
||||
palLineSetPushPull(tx_line, PAL_PUSHPULL_PULLUP);
|
||||
}
|
||||
}
|
||||
// F7 can also support swapping RX and TX pins
|
||||
if (options & OPTION_SWAP) {
|
||||
@ -1325,11 +1381,27 @@ bool UARTDriver::set_options(uint8_t options)
|
||||
if (options & OPTION_HDPLEX) {
|
||||
cr3 |= USART_CR3_HDSEL;
|
||||
_cr3_options |= USART_CR3_HDSEL;
|
||||
half_duplex = true;
|
||||
if (!half_duplex) {
|
||||
chEvtRegisterMaskWithFlags(chnGetEventSource((SerialDriver*)sdef.serial),
|
||||
&hd_listener,
|
||||
EVT_TRANSMIT_END,
|
||||
CHN_OUTPUT_EMPTY);
|
||||
half_duplex = true;
|
||||
}
|
||||
#ifndef HAL_UART_NODMA
|
||||
if (rx_dma_enabled && rxdma) {
|
||||
dmaStreamDisable(rxdma);
|
||||
}
|
||||
#endif
|
||||
// force DMA off when using half-duplex as the timing may affect other devices
|
||||
// sharing the DMA channel
|
||||
rx_dma_enabled = tx_dma_enabled = false;
|
||||
} else {
|
||||
cr3 &= ~USART_CR3_HDSEL;
|
||||
}
|
||||
|
||||
set_pushpull(options);
|
||||
|
||||
if (sd->usart->CR2 == cr2 &&
|
||||
sd->usart->CR3 == cr3) {
|
||||
// no change
|
||||
@ -1356,4 +1428,34 @@ uint8_t UARTDriver::get_options(void) const
|
||||
return _last_options;
|
||||
}
|
||||
|
||||
#if HAL_USE_SERIAL_USB == TRUE
|
||||
/*
|
||||
initialise the USB bus, called from both UARTDriver and stdio for startup debug
|
||||
This can be called before the hal is initialised so must not call any hal functions
|
||||
*/
|
||||
void usb_initialise(void)
|
||||
{
|
||||
static bool initialised;
|
||||
if (initialised) {
|
||||
return;
|
||||
}
|
||||
initialised = true;
|
||||
sduObjectInit(&SDU1);
|
||||
sduStart(&SDU1, &serusbcfg1);
|
||||
#if HAL_HAVE_DUAL_USB_CDC
|
||||
sduObjectInit(&SDU2);
|
||||
sduStart(&SDU2, &serusbcfg2);
|
||||
#endif
|
||||
/*
|
||||
* Activates the USB driver and then the USB bus pull-up on D+.
|
||||
* Note, a delay is inserted in order to not have to disconnect the cable
|
||||
* after a reset.
|
||||
*/
|
||||
usbDisconnectBus(serusbcfg1.usbp);
|
||||
chThdSleep(chTimeUS2I(1500));
|
||||
usbStart(serusbcfg1.usbp, &usbcfg);
|
||||
usbConnectBus(serusbcfg1.usbp);
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
|
@ -22,7 +22,7 @@
|
||||
#include "shared_dma.h"
|
||||
#include "Semaphores.h"
|
||||
|
||||
#define RX_BOUNCE_BUFSIZE 128U
|
||||
#define RX_BOUNCE_BUFSIZE 64U
|
||||
#define TX_BOUNCE_BUFSIZE 64U
|
||||
|
||||
// enough for uartA to uartH, plus IOMCU
|
||||
@ -54,7 +54,7 @@ public:
|
||||
bool lock_port(uint32_t write_key, uint32_t read_key) override;
|
||||
|
||||
// control optional features
|
||||
bool set_options(uint8_t options) override;
|
||||
bool set_options(uint16_t options) override;
|
||||
uint8_t get_options(void) const override;
|
||||
|
||||
// write to a locked port. If port is locked and key is not correct then 0 is returned
|
||||
@ -72,6 +72,8 @@ public:
|
||||
uint8_t dma_tx_stream_id;
|
||||
uint32_t dma_tx_channel_id;
|
||||
#endif
|
||||
ioline_t tx_line;
|
||||
ioline_t rx_line;
|
||||
ioline_t rts_line;
|
||||
int8_t rxinv_gpio;
|
||||
uint8_t rxinv_polarity;
|
||||
@ -117,6 +119,8 @@ public:
|
||||
|
||||
private:
|
||||
const SerialDef &sdef;
|
||||
bool rx_dma_enabled;
|
||||
bool tx_dma_enabled;
|
||||
|
||||
// thread used for all UARTs
|
||||
static thread_t *uart_thread_ctx;
|
||||
@ -149,12 +153,13 @@ private:
|
||||
// of ::read() and ::write() in the main loop
|
||||
#ifndef HAL_UART_NODMA
|
||||
bool tx_bounce_buf_ready;
|
||||
uint8_t *rx_bounce_buf;
|
||||
volatile uint8_t rx_bounce_idx;
|
||||
uint8_t *rx_bounce_buf[2];
|
||||
uint8_t *tx_bounce_buf;
|
||||
#endif
|
||||
ByteBuffer _readbuf{0};
|
||||
ByteBuffer _writebuf{0};
|
||||
Semaphore _write_mutex;
|
||||
HAL_Semaphore _write_mutex;
|
||||
#ifndef HAL_UART_NODMA
|
||||
const stm32_dma_stream_t* rxdma;
|
||||
const stm32_dma_stream_t* txdma;
|
||||
@ -164,7 +169,6 @@ private:
|
||||
bool _blocking_writes;
|
||||
bool _initialised;
|
||||
bool _device_initialised;
|
||||
bool _lock_rx_in_timer_tick = false;
|
||||
#ifndef HAL_UART_NODMA
|
||||
Shared_DMA *dma_handle;
|
||||
#endif
|
||||
@ -181,17 +185,20 @@ private:
|
||||
uint32_t _first_write_started_us;
|
||||
uint32_t _total_written;
|
||||
|
||||
// we remember cr2 and cr2 options from set_options to apply on sdStart()
|
||||
uint32_t _cr3_options;
|
||||
// we remember config options from set_options to apply on sdStart()
|
||||
uint32_t _cr1_options;
|
||||
uint32_t _cr2_options;
|
||||
uint8_t _last_options;
|
||||
uint32_t _cr3_options;
|
||||
uint16_t _last_options;
|
||||
|
||||
// half duplex control. After writing we throw away bytes for 4 byte widths to
|
||||
// prevent reading our own bytes back
|
||||
#if CH_CFG_USE_EVENTS == TRUE
|
||||
bool half_duplex;
|
||||
uint32_t hd_read_delay_us;
|
||||
uint32_t hd_write_us;
|
||||
void half_duplex_setup_delay(uint16_t len);
|
||||
event_listener_t hd_listener;
|
||||
bool hd_tx_active;
|
||||
void half_duplex_setup_tx(void);
|
||||
#endif
|
||||
|
||||
// set to true for unbuffered writes (low latency writes)
|
||||
bool unbuffered_writes;
|
||||
@ -212,6 +219,7 @@ private:
|
||||
#ifndef HAL_UART_NODMA
|
||||
void dma_tx_allocate(Shared_DMA *ctx);
|
||||
void dma_tx_deallocate(Shared_DMA *ctx);
|
||||
void dma_rx_enable(void);
|
||||
#endif
|
||||
void update_rts_line(void);
|
||||
|
||||
@ -224,6 +232,12 @@ private:
|
||||
|
||||
void receive_timestamp_update(void);
|
||||
|
||||
// set SERIALn_OPTIONS for pullup/pulldown
|
||||
void set_pushpull(uint16_t options);
|
||||
|
||||
void thread_init();
|
||||
static void uart_thread(void *);
|
||||
};
|
||||
|
||||
// access to usb init for stdio.cpp
|
||||
void usb_initialise(void);
|
||||
|
13
libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/defaults.parm
Executable file
13
libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/defaults.parm
Executable file
@ -0,0 +1,13 @@
|
||||
# setup the temperature compensation
|
||||
BRD_IMU_TARGTEMP 45
|
||||
|
||||
# turn on the CAN power monitoring(default)
|
||||
CAN_P1_DRIVER 1
|
||||
BATT_MONITOR 8
|
||||
|
||||
# setup the parameter for the ADC power module
|
||||
BATT_VOLT_PIN 16
|
||||
BATT_CURR_PIN 17
|
||||
BATT_VOLT_MULT 18.000
|
||||
BATT_AMP_PERVLT 24.000
|
||||
|
62
libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef-bl.dat
Executable file
62
libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef-bl.dat
Executable file
@ -0,0 +1,62 @@
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for CUAV-Nora board
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1009
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
# the H743 has 128k sectors
|
||||
FLASH_BOOTLOADER_LOAD_KB 128
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 2
|
||||
|
||||
PD8 LED_RED OUTPUT OPENDRAIN HIGH # red
|
||||
PC7 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # blue
|
||||
PC6 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # green
|
||||
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 is debug
|
||||
PF6 UART7_RX UART7 NODMA
|
||||
PE8 UART7_TX UART7 NODMA
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
define HAL_USE_EMPTY_STORAGE 1
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
define BOOTLOADER_DEBUG SD7
|
||||
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PF10 ADIS16470_CS CS
|
||||
PF2 RM3100_CS CS
|
||||
PG6 ICM20689_CS CS SPEED_VERYLOW
|
||||
PI12 ICM20649_CS CS SPEED_VERYLOW
|
||||
PF3 BMI088_A_CS CS
|
||||
PF4 BMI088_G_CS CS
|
||||
PF5 FRAM_CS CS SPEED_VERYLOW
|
||||
PG10 MS5611_IMU_CS CS
|
||||
PI8 MS5611_BOARD_CS CS
|
||||
PI4 EXT1_CS1 CS
|
||||
PI10 EXT1_CS2 CS
|
||||
PI6 EXT1_CS3 CS
|
295
libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat
Executable file
295
libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat
Executable file
@ -0,0 +1,295 @@
|
||||
# hw definition file for processing by chibios_hwdef.py for CUAV-Nora
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1009
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# with 2M flash we can afford to optimize for speed
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 2
|
||||
|
||||
# bootloader takes first sector
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART2 USART6 USART1 UART4 UART8 UART7 OTG2
|
||||
|
||||
# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
||||
# now we define the pins that USB is connected on
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# Port switching for USB HS and FS,high = USB_FS , LOW = USB_HS
|
||||
PH15 USB_HS_ENABLE OUTPUT HIGH
|
||||
define USB_HW_ENABLE_HS 0
|
||||
|
||||
# these are the pins for SWD debugging with a STlinkv2 or black-magic probe
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# SPI1 - internal sensors
|
||||
PG11 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PD7 SPI1_MOSI SPI1
|
||||
|
||||
# SPI2 - FRAM
|
||||
PI1 SPI2_SCK SPI2
|
||||
PI2 SPI2_MISO SPI2
|
||||
PI3 SPI2_MOSI SPI2
|
||||
|
||||
# SPI4 - sensors2
|
||||
PE2 SPI4_SCK SPI4
|
||||
PE13 SPI4_MISO SPI4
|
||||
PE6 SPI4_MOSI SPI4
|
||||
|
||||
# SPI5 - external1
|
||||
PF7 SPI5_SCK SPI5
|
||||
PF8 SPI5_MISO SPI5
|
||||
PF9 SPI5_MOSI SPI5
|
||||
|
||||
# SPI6 - external2
|
||||
PG13 SPI6_SCK SPI6
|
||||
PG12 SPI6_MISO SPI6
|
||||
PA7 SPI6_MOSI SPI6
|
||||
|
||||
# sensor
|
||||
|
||||
PF10 ADIS16470_CS CS
|
||||
PF2 RM3100_CS CS
|
||||
PG6 ICM20689_CS CS SPEED_VERYLOW
|
||||
PI12 ICM20649_CS CS SPEED_VERYLOW
|
||||
PF3 BMI088_A_CS CS
|
||||
PF4 BMI088_G_CS CS
|
||||
PF5 FRAM_CS CS SPEED_VERYLOW
|
||||
PG10 MS5611_IMU_CS CS
|
||||
PI8 MS5611_BOARD_CS CS
|
||||
|
||||
# external CS pins, SPI5 connector
|
||||
PI4 EXT1_CS1 CS
|
||||
PI10 EXT1_CS2 CS
|
||||
PI6 EXT1_CS3 CS
|
||||
|
||||
# I2C buses
|
||||
|
||||
# I2C1 is on GPS port
|
||||
PB8 I2C1_SCL I2C1
|
||||
PB9 I2C1_SDA I2C1
|
||||
|
||||
# I2C2 on GPS2 connector
|
||||
PF1 I2C2_SCL I2C2
|
||||
PF0 I2C2_SDA I2C2
|
||||
|
||||
# I2C3 for onboard mag
|
||||
PH7 I2C3_SCL I2C3
|
||||
PH8 I2C3_SDA I2C3
|
||||
|
||||
# I2C4 is on BDMA on DMAMUX2
|
||||
PF14 I2C4_SCL I2C4
|
||||
PF15 I2C4_SDA I2C4
|
||||
|
||||
# order of I2C buses
|
||||
I2C_ORDER I2C3 I2C1 I2C2 I2C4
|
||||
|
||||
define HAL_I2C_INTERNAL_MASK 1
|
||||
|
||||
# enable pins
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
|
||||
|
||||
# start peripheral power off, then enable after init
|
||||
# this prevents a problem with radios that use RTS for
|
||||
# bootloader hold
|
||||
PD11 VDD_5V_HIPOWER_EN OUTPUT HIGH
|
||||
PG4 VDD_5V_PERIPH_EN OUTPUT HIGH
|
||||
|
||||
PG5 VDD_5V_RC_EN OUTPUT HIGH
|
||||
PG7 VDD_3V3_SD_CARD_EN OUTPUT HIGH
|
||||
|
||||
# drdy pins
|
||||
PE7 DRDY1_ADIS16470 INPUT
|
||||
PH5 DRDY2_ICM20649 INPUT
|
||||
PB14 DRDY3_BMI088_GYRO1 INPUT
|
||||
PB15 DRDY4_BMI088_ACC1 INPUT
|
||||
PJ0 DRDY5_ICM20689 INPUT
|
||||
PC13 DRDY6_BMI088_GYRO2 INPUT
|
||||
PI14 DRDY7_BMI088_ACC2 INPUT
|
||||
PE4 DRDY8_RM3100 INPUT
|
||||
|
||||
# UARTs
|
||||
|
||||
# USART2 is telem1
|
||||
PD6 USART2_RX USART2
|
||||
PD5 USART2_TX USART2
|
||||
PD3 USART2_CTS USART2
|
||||
PD4 USART2_RTS USART2
|
||||
|
||||
# USART1 is GPS1
|
||||
PB7 USART1_RX USART1 NODMA
|
||||
PB6 USART1_TX USART1 NODMA
|
||||
|
||||
# UART4 GPS2
|
||||
PD0 UART4_RX UART4 NODMA
|
||||
PD1 UART4_TX UART4 NODMA
|
||||
|
||||
# USART6 is telem2
|
||||
PG9 USART6_RX USART6
|
||||
PG14 USART6_TX USART6
|
||||
PG15 USART6_CTS USART6
|
||||
PG8 USART6_RTS USART6
|
||||
|
||||
# UART7 is debug
|
||||
PF6 UART7_RX UART7 NODMA
|
||||
PE8 UART7_TX UART7 NODMA
|
||||
|
||||
# SBUS, DSM port
|
||||
PE0 UART8_RX UART8
|
||||
PE1 UART8_TX UART8
|
||||
|
||||
# PWM AUX channels
|
||||
PH10 TIM5_CH1 TIM5 PWM(1) GPIO(50)
|
||||
PH11 TIM5_CH2 TIM5 PWM(2) GPIO(51)
|
||||
PH12 TIM5_CH3 TIM5 PWM(3) GPIO(52)
|
||||
PI0 TIM5_CH4 TIM5 PWM(4) GPIO(53)
|
||||
PD12 TIM4_CH1 TIM4 PWM(5) GPIO(54)
|
||||
PD13 TIM4_CH2 TIM4 PWM(6) GPIO(55)
|
||||
PD14 TIM4_CH3 TIM4 PWM(7) GPIO(56)
|
||||
PD15 TIM4_CH4 TIM4 PWM(8) GPIO(57)
|
||||
|
||||
PE9 TIM1_CH1 TIM1 PWM(9) GPIO(58)
|
||||
PE11 TIM1_CH2 TIM1 PWM(10) GPIO(59)
|
||||
PA10 TIM1_CH3 TIM1 PWM(11) GPIO(60)
|
||||
PE14 TIM1_CH4 TIM1 PWM(12) GPIO(61)
|
||||
PH6 TIM12_CH1 TIM12 PWM(13) GPIO(62) NODMA
|
||||
PH9 TIM12_CH2 TIM12 PWM(14) GPIO(63) NODMA
|
||||
|
||||
# WS2812 LED
|
||||
PI5 TIM8_CH1 TIM8 PWM(15) GPIO(64)
|
||||
|
||||
# allow for 15 PWMs by default
|
||||
define BOARD_PWM_COUNT_DEFAULT 15
|
||||
|
||||
# PWM output for buzzer
|
||||
PE5 TIM15_CH1 TIM15 GPIO(77) ALARM
|
||||
|
||||
# RC input
|
||||
PB4 TIM3_CH1 TIM3 RCININT PULLUP LOW
|
||||
|
||||
# analog in
|
||||
PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PA1 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
# ADC3.3/ADC6.6
|
||||
PC4 SPARE1_ADC1 ADC1 SCALE(1)
|
||||
PA4 SPARE2_ADC1 ADC1 SCALE(1)
|
||||
|
||||
PF12 RSSI_IN ADC1 SCALE(1)
|
||||
|
||||
PC5 VDD_5V_SENS ADC1 SCALE(2)
|
||||
PC1 SCALED_V3V3 ADC1 SCALE(2)
|
||||
|
||||
# CAN bus
|
||||
PI9 CAN1_RX CAN1
|
||||
PH13 CAN1_TX CAN1
|
||||
|
||||
# 2nd CAN bus. Cannot be used at same time as USB_HS
|
||||
PB12 CAN2_RX CAN2
|
||||
PB13 CAN2_TX CAN2
|
||||
|
||||
# control for silent (no output) for CAN
|
||||
PH2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)
|
||||
PH3 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71)
|
||||
|
||||
# GPIOs
|
||||
|
||||
PA8 HEATER_EN OUTPUT LOW GPIO(80)
|
||||
define HAL_HEATER_GPIO_PIN 80
|
||||
define HAL_HAVE_IMU_HEATER 1
|
||||
|
||||
PG1 VDD_BRICK_VALID INPUT PULLUP
|
||||
PG2 VDD_BRICK2_VALID INPUT PULLUP
|
||||
PG0 nVBUS INPUT PULLUP
|
||||
PJ3 VDD_5V_HIPOWER_OC INPUT PULLUP
|
||||
PJ4 VDD_5V_PERIPH_OC INPUT PULLUP
|
||||
PB10 nSPI5_RESET_EXTERNAL1 OUTPUT HIGH
|
||||
|
||||
# SPI devices
|
||||
SPIDEV rm3100 SPI1 DEVID1 RM3100_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV icm20689 SPI1 DEVID2 ICM20689_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV bmi088_a SPI4 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV bmi088_g SPI4 DEVID3 BMI088_G_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV ms5611_imu SPI4 DEVID1 MS5611_IMU_CS MODE3 20*MHZ 20*MHZ
|
||||
SPIDEV ms5611_board SPI6 DEVID1 MS5611_BOARD_CS MODE3 20*MHZ 20*MHZ
|
||||
SPIDEV icm20649 SPI6 DEVID2 ICM20649_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
|
||||
# two baro
|
||||
BARO MS56XX SPI:ms5611_imu
|
||||
BARO MS56XX SPI:ms5611_board
|
||||
|
||||
# three IMUs
|
||||
IMU Invensense SPI:icm20689 ROTATION_NONE
|
||||
IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180_YAW_270
|
||||
IMU Invensensev2 SPI:icm20649 ROTATION_NONE
|
||||
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 5
|
||||
|
||||
# compasses
|
||||
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
|
||||
COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_ROLL_180_YAW_90
|
||||
|
||||
COMPASS RM3100 SPI:rm3100 false ROTATION_NONE
|
||||
|
||||
|
||||
# microSD support
|
||||
PC8 SDMMC1_D0 SDMMC1
|
||||
PC9 SDMMC1_D1 SDMMC1
|
||||
PC10 SDMMC1_D2 SDMMC1
|
||||
PC11 SDMMC1_D3 SDMMC1
|
||||
PC12 SDMMC1_CK SDMMC1
|
||||
PD2 SDMMC1_CMD SDMMC1
|
||||
|
||||
# red LED marked as B/E
|
||||
|
||||
PD8 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0)
|
||||
PC6 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1)
|
||||
PC7 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2)
|
||||
|
||||
define HAL_GPIO_A_LED_PIN 0
|
||||
define HAL_GPIO_B_LED_PIN 1
|
||||
define HAL_GPIO_C_LED_PIN 2
|
||||
|
||||
define HAL_GPIO_LED_ON 0
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
||||
# use pixracer style 3-LED indicators
|
||||
define HAL_HAVE_PIXRACER_LED
|
||||
|
||||
# enable RAMTROM parameter storage
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
define HAL_WITH_RAMTRON 1
|
||||
|
||||
# allow to have have a dedicated safety switch pin
|
||||
define HAL_HAVE_SAFETY_SWITCH 1
|
||||
PE12 LED_SAFETY OUTPUT
|
||||
PE10 SAFETY_IN INPUT PULLDOWN
|
||||
|
||||
# enable FAT filesystem support (needs a microSD defined via SDMMC)
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
DMA_PRIORITY ADC* SPI1* TIM*UP*
|
||||
DMA_NOSHARE SPI1* TIM*UP*
|
18
libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/defaults.parm
Normal file
18
libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/defaults.parm
Normal file
@ -0,0 +1,18 @@
|
||||
# temperature control. We need lower P/I values
|
||||
# to prevent oscillation of the BMI088 temperature
|
||||
# the ADIS16470 is factory temperature calibrated,
|
||||
# but the BMI088 isn't, so temperature control is still
|
||||
# worthwhile
|
||||
BRD_IMU_TARGTEMP 45
|
||||
BRD_IMUHEAT_P 50
|
||||
BRD_IMUHEAT_I 0.07
|
||||
|
||||
# turn on the CAN power monitoring(default)
|
||||
CAN_P1_DRIVER 1
|
||||
BATT_MONITOR 8
|
||||
|
||||
# setup the parameter for the ADC power module
|
||||
BATT_VOLT_PIN 16
|
||||
BATT_CURR_PIN 17
|
||||
BATT_VOLT_MULT 18.000
|
||||
BATT_AMP_PERVLT 24.000
|
62
libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef-bl.dat
Normal file
62
libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef-bl.dat
Normal file
@ -0,0 +1,62 @@
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for CUAV-X7 board
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1010
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
# the H743 has 128k sectors
|
||||
FLASH_BOOTLOADER_LOAD_KB 128
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 2
|
||||
|
||||
PI5 LED_RED OUTPUT OPENDRAIN HIGH # red
|
||||
PI7 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # blue
|
||||
PI6 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # green
|
||||
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 is debug
|
||||
PF6 UART7_RX UART7 NODMA
|
||||
PE8 UART7_TX UART7 NODMA
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
define HAL_USE_EMPTY_STORAGE 1
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
define BOOTLOADER_DEBUG SD7
|
||||
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PF10 ADIS16470_CS CS
|
||||
PF2 RM3100_CS CS
|
||||
PG6 ICM20689_CS CS SPEED_VERYLOW
|
||||
PI12 ICM20649_CS CS SPEED_VERYLOW
|
||||
PF3 BMI088_A_CS CS
|
||||
PF4 BMI088_G_CS CS
|
||||
PF5 FRAM_CS CS SPEED_VERYLOW
|
||||
PG10 MS5611_IMU_CS CS
|
||||
PI8 MS5611_BOARD_CS CS
|
||||
PI4 EXT1_CS1 CS
|
||||
PI10 EXT1_CS2 CS
|
||||
PI13 EXT1_CS3 CS
|
306
libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat
Normal file
306
libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat
Normal file
@ -0,0 +1,306 @@
|
||||
# hw definition file for processing by chibios_hwdef.py for CUAV-X7
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1010
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# with 2M flash we can afford to optimize for speed
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 2
|
||||
|
||||
# bootloader takes first sector
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART2 USART6 USART1 UART4 UART8 UART7 OTG2
|
||||
|
||||
# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
||||
# now we define the pins that USB is connected on
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# Port switching for USB HS and FS,high = USB_FS , LOW = USB_HS
|
||||
PH15 USB_HS_ENABLE OUTPUT HIGH
|
||||
define USB_HW_ENABLE_HS 0
|
||||
|
||||
# these are the pins for SWD debugging with a STlinkv2 or black-magic probe
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# SPI1 - internal sensors
|
||||
PG11 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PD7 SPI1_MOSI SPI1
|
||||
|
||||
# SPI2 - FRAM
|
||||
PI1 SPI2_SCK SPI2
|
||||
PI2 SPI2_MISO SPI2
|
||||
PI3 SPI2_MOSI SPI2
|
||||
|
||||
# SPI4 - sensors2
|
||||
PE2 SPI4_SCK SPI4
|
||||
PE13 SPI4_MISO SPI4
|
||||
PE6 SPI4_MOSI SPI4
|
||||
|
||||
# SPI5 - external1
|
||||
PF7 SPI5_SCK SPI5
|
||||
PF8 SPI5_MISO SPI5
|
||||
PF9 SPI5_MOSI SPI5
|
||||
|
||||
# SPI6 - external2
|
||||
PG13 SPI6_SCK SPI6
|
||||
PG12 SPI6_MISO SPI6
|
||||
PA7 SPI6_MOSI SPI6
|
||||
|
||||
# sensor
|
||||
|
||||
PF10 ADIS16470_CS CS
|
||||
PF2 RM3100_CS CS
|
||||
PG6 ICM20689_CS CS SPEED_VERYLOW
|
||||
PI12 ICM20649_CS CS SPEED_VERYLOW
|
||||
PF3 BMI088_A_CS CS
|
||||
PF4 BMI088_G_CS CS
|
||||
PF5 FRAM_CS CS SPEED_VERYLOW
|
||||
PG10 MS5611_IMU_CS CS
|
||||
PI8 MS5611_BOARD_CS CS
|
||||
|
||||
# external CS pins, SPI5 connector
|
||||
PI4 EXT1_CS1 CS
|
||||
PI10 EXT1_CS2 CS
|
||||
PI13 EXT1_CS3 CS
|
||||
|
||||
# I2C buses
|
||||
|
||||
# I2C1 is on GPS port
|
||||
PB8 I2C1_SCL I2C1
|
||||
PB9 I2C1_SDA I2C1
|
||||
|
||||
# I2C2 on GPS2 connector
|
||||
PF1 I2C2_SCL I2C2
|
||||
PF0 I2C2_SDA I2C2
|
||||
|
||||
# I2C3 for onboard mag
|
||||
PH7 I2C3_SCL I2C3
|
||||
PH8 I2C3_SDA I2C3
|
||||
|
||||
# I2C4 is on BDMA on DMAMUX2
|
||||
PF14 I2C4_SCL I2C4
|
||||
PF15 I2C4_SDA I2C4
|
||||
|
||||
# order of I2C buses
|
||||
I2C_ORDER I2C3 I2C1 I2C2 I2C4
|
||||
|
||||
define HAL_I2C_INTERNAL_MASK 1
|
||||
|
||||
# enable pins
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
|
||||
|
||||
# start peripheral power off, then enable after init
|
||||
# this prevents a problem with radios that use RTS for
|
||||
# bootloader hold
|
||||
PD11 VDD_5V_HIPOWER_EN OUTPUT HIGH
|
||||
PG4 VDD_5V_PERIPH_EN OUTPUT HIGH
|
||||
|
||||
PG5 VDD_5V_RC_EN OUTPUT HIGH
|
||||
PG7 VDD_3V3_SD_CARD_EN OUTPUT HIGH
|
||||
|
||||
# drdy pins
|
||||
PE7 DRDY1_ADIS16470 INPUT GPIO(93)
|
||||
PH5 DRDY2_ICM20649 INPUT
|
||||
PB14 DRDY3_BMI088_GYRO1 INPUT
|
||||
PB15 DRDY4_BMI088_ACC1 INPUT
|
||||
PJ0 DRDY5_ICM20689 INPUT
|
||||
PC13 DRDY6_BMI088_GYRO2 INPUT
|
||||
PI14 DRDY7_BMI088_ACC2 INPUT
|
||||
PE4 DRDY8_RM3100 INPUT
|
||||
|
||||
# use GPIO(93) for data ready on ADIS16470
|
||||
define ADIS_DRDY_PIN 93
|
||||
|
||||
# UARTs
|
||||
|
||||
# USART2 is telem1
|
||||
PD6 USART2_RX USART2
|
||||
PD5 USART2_TX USART2
|
||||
PD3 USART2_CTS USART2
|
||||
PD4 USART2_RTS USART2
|
||||
|
||||
# USART1 is GPS1
|
||||
PB7 USART1_RX USART1 NODMA
|
||||
PB6 USART1_TX USART1 NODMA
|
||||
|
||||
# UART4 GPS2
|
||||
PD0 UART4_RX UART4 NODMA
|
||||
PD1 UART4_TX UART4 NODMA
|
||||
|
||||
# USART6 is telem2
|
||||
PG9 USART6_RX USART6
|
||||
PG14 USART6_TX USART6
|
||||
PG15 USART6_CTS USART6
|
||||
PG8 USART6_RTS USART6
|
||||
|
||||
# UART7 is debug
|
||||
PF6 UART7_RX UART7 NODMA
|
||||
PE8 UART7_TX UART7 NODMA
|
||||
|
||||
# SBUS, DSM port
|
||||
PE0 UART8_RX UART8
|
||||
PE1 UART8_TX UART8
|
||||
|
||||
# PWM AUX channels
|
||||
PH10 TIM5_CH1 TIM5 PWM(1) GPIO(50)
|
||||
PH11 TIM5_CH2 TIM5 PWM(2) GPIO(51)
|
||||
PH12 TIM5_CH3 TIM5 PWM(3) GPIO(52)
|
||||
PI0 TIM5_CH4 TIM5 PWM(4) GPIO(53)
|
||||
PD12 TIM4_CH1 TIM4 PWM(5) GPIO(54)
|
||||
PD13 TIM4_CH2 TIM4 PWM(6) GPIO(55)
|
||||
PD14 TIM4_CH3 TIM4 PWM(7) GPIO(56)
|
||||
PD15 TIM4_CH4 TIM4 PWM(8) GPIO(57)
|
||||
|
||||
PE9 TIM1_CH1 TIM1 PWM(9) GPIO(58)
|
||||
PE11 TIM1_CH2 TIM1 PWM(10) GPIO(59)
|
||||
PA10 TIM1_CH3 TIM1 PWM(11) GPIO(60)
|
||||
PE14 TIM1_CH4 TIM1 PWM(12) GPIO(61)
|
||||
PH6 TIM12_CH1 TIM12 PWM(13) GPIO(62) NODMA
|
||||
PH9 TIM12_CH2 TIM12 PWM(14) GPIO(63) NODMA
|
||||
|
||||
# allow for 14 PWMs by default
|
||||
define BOARD_PWM_COUNT_DEFAULT 14
|
||||
|
||||
# PWM output for buzzer
|
||||
PE5 TIM15_CH1 TIM15 GPIO(77) ALARM
|
||||
|
||||
# RC input
|
||||
PB4 TIM3_CH1 TIM3 RCININT PULLUP LOW
|
||||
|
||||
# analog in
|
||||
PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PA1 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
# ADC3.3/ADC6.6
|
||||
PC4 SPARE1_ADC1 ADC1 SCALE(1)
|
||||
PA4 SPARE2_ADC1 ADC1 SCALE(1)
|
||||
|
||||
PF12 RSSI_IN ADC1 SCALE(1)
|
||||
|
||||
PC5 VDD_5V_SENS ADC1 SCALE(2)
|
||||
PC1 SCALED_V3V3 ADC1 SCALE(2)
|
||||
|
||||
# CAN bus
|
||||
PI9 CAN1_RX CAN1
|
||||
PH13 CAN1_TX CAN1
|
||||
|
||||
# 2nd CAN bus. Cannot be used at same time as USB_HS
|
||||
PB12 CAN2_RX CAN2
|
||||
PB13 CAN2_TX CAN2
|
||||
|
||||
# control for silent (no output) for CAN
|
||||
PH2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)
|
||||
PH3 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71)
|
||||
|
||||
# GPIOs
|
||||
|
||||
PA8 HEATER_EN OUTPUT LOW GPIO(80)
|
||||
define HAL_HEATER_GPIO_PIN 80
|
||||
define HAL_HAVE_IMU_HEATER 1
|
||||
|
||||
PG1 VDD_BRICK_VALID INPUT PULLUP
|
||||
PG2 VDD_BRICK2_VALID INPUT PULLUP
|
||||
PG0 nVBUS INPUT PULLUP
|
||||
PJ3 VDD_5V_HIPOWER_OC INPUT PULLUP
|
||||
PJ4 VDD_5V_PERIPH_OC INPUT PULLUP
|
||||
PB10 nSPI5_RESET_EXTERNAL1 OUTPUT HIGH
|
||||
|
||||
# SPI devices
|
||||
SPIDEV adis16470 SPI1 DEVID2 ADIS16470_CS MODE3 1*MHZ 2*MHZ
|
||||
SPIDEV icm20689 SPI1 DEVID2 ICM20689_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV bmi088_a SPI4 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV bmi088_g SPI4 DEVID3 BMI088_G_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV ms5611_imu SPI4 DEVID1 MS5611_IMU_CS MODE3 20*MHZ 20*MHZ
|
||||
SPIDEV ms5611_board SPI6 DEVID1 MS5611_BOARD_CS MODE3 20*MHZ 20*MHZ
|
||||
SPIDEV icm20649 SPI6 DEVID2 ICM20649_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
|
||||
# RM3100 may be on SPI1 or SPI2 (not both). Later board revisions
|
||||
# have the RM3100 on SPI2, to leave SPI1 free for ADIS1647x
|
||||
SPIDEV rm3100-1 SPI1 DEVID1 RM3100_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV rm3100-2 SPI2 DEVID2 RM3100_CS MODE3 2*MHZ 8*MHZ
|
||||
|
||||
# two baro
|
||||
BARO MS56XX SPI:ms5611_imu
|
||||
BARO MS56XX SPI:ms5611_board
|
||||
|
||||
# three IMUs, only one of ICM20689 and ADIS16470 will be included
|
||||
IMU ADIS1647x SPI:adis16470 ROTATION_PITCH_180_YAW_270 ADIS_DRDY_PIN
|
||||
IMU Invensense SPI:icm20689 ROTATION_NONE
|
||||
IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180_YAW_270
|
||||
IMU Invensensev2 SPI:icm20649 ROTATION_NONE
|
||||
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 5
|
||||
|
||||
# compasses
|
||||
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
|
||||
COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_ROLL_180_YAW_90
|
||||
|
||||
# probe for RM3100 on SPI1 or SPI2
|
||||
COMPASS RM3100 SPI:rm3100-1 false ROTATION_NONE
|
||||
COMPASS RM3100 SPI:rm3100-2 false ROTATION_NONE
|
||||
|
||||
|
||||
# microSD support
|
||||
PC8 SDMMC1_D0 SDMMC1
|
||||
PC9 SDMMC1_D1 SDMMC1
|
||||
PC10 SDMMC1_D2 SDMMC1
|
||||
PC11 SDMMC1_D3 SDMMC1
|
||||
PC12 SDMMC1_CK SDMMC1
|
||||
PD2 SDMMC1_CMD SDMMC1
|
||||
|
||||
# red LED marked as B/E
|
||||
|
||||
PI5 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0)
|
||||
PI6 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1)
|
||||
PI7 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2)
|
||||
|
||||
define HAL_GPIO_A_LED_PIN 0
|
||||
define HAL_GPIO_B_LED_PIN 1
|
||||
define HAL_GPIO_C_LED_PIN 2
|
||||
|
||||
define HAL_GPIO_LED_ON 0
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
||||
# use pixracer style 3-LED indicators
|
||||
define HAL_HAVE_PIXRACER_LED
|
||||
|
||||
# enable RAMTROM parameter storage
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
define HAL_WITH_RAMTRON 1
|
||||
|
||||
# allow to have have a dedicated safety switch pin
|
||||
define HAL_HAVE_SAFETY_SWITCH 1
|
||||
PE12 LED_SAFETY OUTPUT
|
||||
PE10 SAFETY_IN INPUT PULLDOWN
|
||||
|
||||
# enable FAT filesystem support (needs a microSD defined via SDMMC)
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
DMA_PRIORITY ADC* SPI1* TIM*UP*
|
||||
DMA_NOSHARE SPI1* TIM*UP*
|
||||
|
||||
# default to 45C target temp
|
||||
define HAL_IMU_TEMP_DEFAULT 45
|
@ -16,19 +16,6 @@ env AP_PERIPH 1
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
STM32_HSE_ENABLED TRUE
|
||||
STM32_PLLM_VALUE 16
|
||||
STM32_PLLN_VALUE 384
|
||||
STM32_PLLP_VALUE 4
|
||||
STM32_PLLQ_VALUE 8
|
||||
STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
STM32_PREE1 STM32_PREE1_DIV1
|
||||
STM32_PREE2 STM32_PREE2_DIV1
|
||||
STM32_HPRE STM32_HPRE_DIV1
|
||||
STM32_PPRE1 STM32_PPRE1_DIV2
|
||||
STM32_PPRE2 STM32_PPRE2_DIV2
|
||||
|
||||
|
||||
define CH_CFG_ST_FREQUENCY 1000000
|
||||
|
||||
# assume 512k flash part
|
||||
@ -37,11 +24,8 @@ FLASH_SIZE_KB 512
|
||||
STDOUT_SERIAL SD1
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER
|
||||
SERIAL_ORDER
|
||||
|
||||
# use safety button to stay in bootloader
|
||||
PB3 STAY_IN_BOOTLOADER INPUT PULLDOWN
|
||||
@ -96,8 +80,8 @@ define STM32_CAN_USE_CAN1 TRUE
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps"
|
||||
|
||||
# start with a fixed node ID so the board is usable without DNA
|
||||
define HAL_CAN_DEFAULT_NODE_ID 116
|
||||
# use DNA
|
||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
@ -25,19 +25,6 @@ define HAL_WATCHDOG_ENABLED_DEFAULT true
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
STM32_HSE_ENABLED TRUE
|
||||
STM32_PLLM_VALUE 16
|
||||
STM32_PLLN_VALUE 384
|
||||
STM32_PLLP_VALUE 4
|
||||
STM32_PLLQ_VALUE 8
|
||||
STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
STM32_PREE1 STM32_PREE1_DIV1
|
||||
STM32_PREE2 STM32_PREE2_DIV1
|
||||
STM32_HPRE STM32_HPRE_DIV1
|
||||
STM32_PPRE1 STM32_PPRE1_DIV2
|
||||
STM32_PPRE2 STM32_PPRE2_DIV2
|
||||
|
||||
|
||||
define CH_CFG_ST_FREQUENCY 1000000
|
||||
|
||||
# assume 512k flash part
|
||||
@ -46,11 +33,8 @@ FLASH_SIZE_KB 512
|
||||
STDOUT_SERIAL SD1
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER USART1 USART2
|
||||
SERIAL_ORDER USART1 EMPTY EMPTY USART2
|
||||
|
||||
# a LED to flash
|
||||
PB12 LED OUTPUT LOW
|
||||
@ -82,11 +66,26 @@ define HAL_I2C_INTERNAL_MASK 0
|
||||
# only one I2C bus
|
||||
I2C_ORDER I2C3
|
||||
|
||||
# IST compass
|
||||
COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180_YAW_90
|
||||
# only one SPI bus in normal config
|
||||
PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
|
||||
# BMP388 baro
|
||||
# SPI CS
|
||||
PA4 MAG_CS CS
|
||||
PA10 MS5611_CS CS
|
||||
|
||||
# SPI devices
|
||||
SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ
|
||||
SPIDEV ms5611 SPI1 DEVID2 MS5611_CS MODE3 20*MHZ 20*MHZ
|
||||
|
||||
# compass
|
||||
COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180_YAW_90
|
||||
COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180
|
||||
|
||||
# baro
|
||||
BARO BMP388 I2C:0:0x76
|
||||
BARO MS56XX SPI:ms5611
|
||||
|
||||
# PWM output for buzzer
|
||||
PB10 TIM2_CH3 TIM2 GPIO(77) LOW ALARM
|
||||
@ -129,13 +128,11 @@ PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
define HAL_USE_CAN TRUE
|
||||
define STM32_CAN_USE_CAN1 TRUE
|
||||
|
||||
# start with a fixed node ID so the board is usable without DNA
|
||||
define HAL_CAN_DEFAULT_NODE_ID 116
|
||||
# use DNA
|
||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps"
|
||||
|
||||
define CH_DBG_ENABLE_STACK_CHECK TRUE
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_LOGGING
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
@ -7,14 +7,6 @@ MCU STM32F7xx STM32F767xx
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
define STM32_LSECLK 32768U
|
||||
define STM32_LSEDRV (3U << 3U)
|
||||
define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
define STM32_PLLM_VALUE 8
|
||||
define STM32_PLLN_VALUE 216
|
||||
define STM32_PLLP_VALUE 2
|
||||
define STM32_PLLQ_VALUE 9
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 50
|
||||
|
||||
@ -34,11 +26,8 @@ PC6 LED_BOOTLOADER OUTPUT HIGH
|
||||
PC7 LED_ACTIVITY OUTPUT HIGH
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2 UART7
|
||||
SERIAL_ORDER OTG1 USART2 UART7
|
||||
|
||||
# USART2 is telem1
|
||||
PD6 USART2_RX USART2
|
||||
|
@ -13,7 +13,7 @@ undef PE3
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
|
||||
|
||||
# order of UARTs (and USB).
|
||||
UART_ORDER OTG1 USART1 USART2 USART3 UART4 USART6 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 USART3 USART1 UART4 USART6 UART7 OTG2
|
||||
|
||||
# enable TX on USART6 (disabled for fmuv5 with iomcu)
|
||||
PG14 USART6_TX USART6 NODMA
|
||||
|
@ -24,6 +24,29 @@ PB1 PB1_ADC ADC1 SCALE(1)
|
||||
SPIDEV icm20948_ext SPI4 DEVID1 MPU_EXT_CS MODE3 4*MHZ 8*MHZ
|
||||
SPIDEV icm20602_ext SPI4 DEVID3 GYRO_EXT_CS MODE3 4*MHZ 8*MHZ
|
||||
|
||||
|
||||
# Sensor Check alias for validating board type
|
||||
CHECK_MPU9250 spi_check_register("mpu9250", MPUREG_WHOAMI, MPU_WHOAMI_MPU9250)
|
||||
CHECK_MPU9250_EXT spi_check_register("mpu9250_ext", MPUREG_WHOAMI, MPU_WHOAMI_MPU9250)
|
||||
CHECK_ICM20602_EXT spi_check_register("icm20602_ext", MPUREG_WHOAMI, MPU_WHOAMI_ICM20602)
|
||||
CHECK_LSM9DS0_EXT_G spi_check_register("lsm9ds0_ext_g", LSMREG_WHOAMI, LSM_WHOAMI_L3GD20)
|
||||
CHECK_LSM9DS0_EXT_AM spi_check_register("lsm9ds0_ext_am", LSMREG_WHOAMI, LSM_WHOAMI_LSM303D)
|
||||
CHECK_ICM20948_EXT spi_check_register("icm20948_ext", INV2REG_WHOAMI, INV2_WHOAMI_ICM20948)
|
||||
CHECK_MS5611 check_ms5611("ms5611")
|
||||
CHECK_MS5611_EXT check_ms5611("ms5611_ext")
|
||||
|
||||
# Sensor Check Macros to be used for validating board type
|
||||
CHECK_IMU0_PRESENT $CHECK_MPU9250_EXT || $CHECK_ICM20602_EXT
|
||||
CHECK_IMU1_PRESENT ($CHECK_LSM9DS0_EXT_G && $CHECK_LSM9DS0_EXT_AM) || $CHECK_ICM20948_EXT
|
||||
CHECK_IMU2_PRESENT $CHECK_MPU9250
|
||||
CHECK_BARO0_PRESENT $CHECK_MS5611
|
||||
CHECK_BARO1_PRESENT $CHECK_MS5611_EXT
|
||||
|
||||
BOARD_VALIDATE $CHECK_IMU0_PRESENT $CHECK_IMU1_PRESENT $CHECK_IMU2_PRESENT $CHECK_BARO0_PRESENT $CHECK_BARO1_PRESENT
|
||||
|
||||
# also define the default board type
|
||||
define BOARD_TYPE_DEFAULT 3
|
||||
|
||||
# three IMUs, but allow for different varients. First two IMUs are
|
||||
# isolated, 3rd isn't
|
||||
IMU Invensense SPI:mpu9250_ext ROTATION_PITCH_180
|
||||
|
@ -28,11 +28,8 @@ FLASH_BOOTLOADER_LOAD_KB 128
|
||||
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART7
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters).
|
||||
PE7 UART7_RX UART7
|
||||
|
@ -23,16 +23,13 @@ env OPTIMIZE -O2
|
||||
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
# order of I2C buses
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2
|
||||
|
||||
# If the board has an IOMCU connected via a UART then this defines the
|
||||
# UART to talk to that MCU. Leave it out for boards with no IOMCU.
|
||||
@ -248,6 +245,23 @@ IMU Invensense SPI:icm20602_ext ROTATION_ROLL_180_YAW_270
|
||||
IMU Invensensev2 SPI:icm20948_ext ROTATION_PITCH_180
|
||||
IMU Invensensev2 SPI:icm20948 ROTATION_YAW_270
|
||||
|
||||
# Sensor Check alias for validating board type
|
||||
CHECK_ICM20649 spi_check_register("icm20948", INV2REG_WHOAMI, INV2_WHOAMI_ICM20649)
|
||||
CHECK_ICM20602_EXT spi_check_register("icm20602_ext", MPUREG_WHOAMI, MPU_WHOAMI_ICM20602)
|
||||
CHECK_ICM20948_EXT spi_check_register("icm20948_ext", INV2REG_WHOAMI, INV2_WHOAMI_ICM20948)
|
||||
CHECK_MS5611 check_ms5611("ms5611")
|
||||
CHECK_MS5611_EXT check_ms5611("ms5611_ext")
|
||||
|
||||
# Sensor Check Macros to be used for validating board type
|
||||
CHECK_IMU0_PRESENT $CHECK_ICM20602_EXT
|
||||
CHECK_IMU1_PRESENT $CHECK_ICM20948_EXT
|
||||
CHECK_IMU2_PRESENT $CHECK_ICM20649
|
||||
CHECK_BARO0_PRESENT $CHECK_MS5611
|
||||
CHECK_BARO1_PRESENT $CHECK_MS5611_EXT
|
||||
|
||||
BOARD_VALIDATE $CHECK_IMU0_PRESENT $CHECK_IMU1_PRESENT $CHECK_IMU2_PRESENT $CHECK_BARO0_PRESENT $CHECK_BARO1_PRESENT
|
||||
|
||||
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 7
|
||||
|
||||
# two baros
|
||||
|
@ -6,20 +6,9 @@ MCU STM32F7xx STM32F777xx
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 24000000
|
||||
|
||||
define STM32_LSECLK 32768U
|
||||
define STM32_LSEDRV (3U << 3U)
|
||||
define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
define STM32_PLLM_VALUE 24
|
||||
define STM32_PLLN_VALUE 432
|
||||
define STM32_PLLP_VALUE 2
|
||||
define STM32_PLLQ_VALUE 9
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 120
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
@ -31,7 +20,7 @@ USB_STRING_PRODUCT "CubeYellow-BL"
|
||||
USB_STRING_SERIAL "%SERIAL%"
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2 USART3 UART7
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART7
|
||||
|
||||
PD5 USART2_TX USART2
|
||||
PD6 USART2_RX USART2
|
||||
|
@ -21,14 +21,6 @@ define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_FMUV3
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 24000000
|
||||
|
||||
define STM32_LSECLK 32768U
|
||||
define STM32_LSEDRV (3U << 3U)
|
||||
define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
define STM32_PLLM_VALUE 24
|
||||
define STM32_PLLN_VALUE 432
|
||||
define STM32_PLLP_VALUE 2
|
||||
define STM32_PLLQ_VALUE 9
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 120
|
||||
|
||||
@ -44,9 +36,6 @@ env OPTIMIZE -O2
|
||||
# now define the voltage the MCU runs at. This is needed for ChibiOS
|
||||
# to set various internal driver limits. It is in 0.01 volt units
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# this is the STM32 timer that ChibiOS will use for the low level
|
||||
# driver. This must be a 32 bit timer. We currently only support
|
||||
# timers 2, 3, 4, 5 and 21. See hal_st_lld.c in ChibiOS for details
|
||||
@ -64,9 +53,9 @@ FLASH_SIZE_KB 2048
|
||||
# in drivers.
|
||||
|
||||
# serial port for stdout. This is optional. If you leave it out then
|
||||
# output from printf() lines will be thrown away (you can stil use
|
||||
# output from printf() lines will be sent to
|
||||
# hal.console->printf() for the ArduPilot console, which is the first
|
||||
# UART in the UART_ORDER list). The value for STDOUT_SERIAL is a
|
||||
# UART in the SERIAL_ORDER list. The value for STDOUT_SERIAL is a
|
||||
# serial device name, and must be for a serial device for which pins
|
||||
# are defined in this file. For example, SD7 is for UART7 (SD7 ==
|
||||
# "serial device 7" in ChibiOS).
|
||||
@ -111,7 +100,7 @@ I2C_ORDER I2C2 I2C1
|
||||
# 6) SERIAL5: extra UART (usually RTOS debug console)
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2
|
||||
|
||||
# if the board has an IOMCU connected via a UART then this defines the
|
||||
# UART to talk to that MCU. Leave it out for boards with no IOMCU
|
||||
@ -469,13 +458,6 @@ define HAL_GPIO_PWM_VOLT_PIN 3
|
||||
# this defines the default maximum clock on I2C devices.
|
||||
define HAL_I2C_MAX_CLOCK 100000
|
||||
|
||||
# uncomment the lines below to enable strict API
|
||||
# checking in ChibiOS
|
||||
# define CH_DBG_ENABLE_ASSERTS TRUE
|
||||
# define CH_DBG_ENABLE_CHECKS TRUE
|
||||
# define CH_DBG_SYSTEM_STATE_CHECK TRUE
|
||||
# define CH_DBG_ENABLE_STACK_CHECK TRUE
|
||||
|
||||
# we can't share IO UART (USART6)
|
||||
DMA_NOSHARE USART6_TX USART6_RX ADC1
|
||||
DMA_PRIORITY USART6*
|
||||
|
@ -10,9 +10,6 @@ APJ_BOARD_ID 13
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 24000000
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 5
|
||||
|
||||
@ -26,7 +23,7 @@ FLASH_BOOTLOADER_LOAD_KB 16
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# uarts and USB to run bootloader protocol on
|
||||
UART_ORDER OTG1 USART2 USART3
|
||||
SERIAL_ORDER OTG1 USART2 USART3
|
||||
|
||||
# this is the pin that senses USB being connected. It is an input pin
|
||||
# setup as OPENDRAIN
|
||||
@ -62,13 +59,6 @@ define HAL_LED_ON 1
|
||||
# available (in bytes)
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
# uncomment the lines below to enable strict API
|
||||
# checking in ChibiOS
|
||||
# define CH_DBG_ENABLE_ASSERTS TRUE
|
||||
# define CH_DBG_ENABLE_CHECKS TRUE
|
||||
# define CH_DBG_SYSTEM_STATE_CHECK TRUE
|
||||
# define CH_DBG_ENABLE_STACK_CHECK TRUE
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PC2 MPU9250_CS CS
|
||||
PC15 20608_CS CS
|
||||
|
@ -1,8 +1,6 @@
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for FMUv4pro hardware (Pixhawk 3 Pro)
|
||||
|
||||
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_FMUV4PRO
|
||||
|
||||
define BOARD_TYPE_DEFAULT 14
|
||||
|
||||
# MCU class and specific type
|
||||
@ -14,8 +12,6 @@ APJ_BOARD_ID 13
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 24000000
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 5
|
||||
@ -44,7 +40,7 @@ I2C_ORDER I2C1 I2C2
|
||||
# 6) SERIAL5: extra UART (usually RTOS debug console)
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1 UART7
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 USART1 UART7
|
||||
|
||||
# UART for IOMCU
|
||||
IOMCU_UART USART6
|
||||
@ -233,9 +229,6 @@ define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
define HAL_WITH_RAMTRON 1
|
||||
|
||||
# fallback to flash is no FRAM fitted
|
||||
define STORAGE_FLASH_PAGE 22
|
||||
|
||||
# enable FAT filesystem support (needs a microSD defined via SDIO)
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
|
@ -32,11 +32,9 @@ PC7 LED_BOOTLOADER OUTPUT LOW # blue
|
||||
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART7
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 is debug
|
||||
PF6 UART7_RX UART7 NODMA
|
||||
@ -48,6 +46,9 @@ PA12 OTG_FS_DP OTG1
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# pullup buzzer for no sound in bootloader
|
||||
PE5 BUZZER OUTPUT LOW PULLDOWN
|
||||
|
||||
define HAL_USE_EMPTY_STORAGE 1
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
|
@ -24,11 +24,9 @@ env OPTIMIZE -O2
|
||||
# bootloader takes first sector
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART2 USART3 UART4 USART6 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 USART3 USART1 UART4 USART6 UART7 OTG2
|
||||
|
||||
# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
@ -9,7 +9,6 @@ APJ_BOARD_ID 135
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
@ -22,11 +21,9 @@ FLASH_BOOTLOADER_LOAD_KB 64
|
||||
define HAL_STORAGE_SIZE 15360
|
||||
define STORAGE_FLASH_PAGE 1
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1 USART1 USART2 UART5
|
||||
SERIAL_ORDER OTG1 USART1 USART2 UART5
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -9,10 +9,6 @@ APJ_BOARD_ID 135
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 5
|
||||
@ -29,7 +25,7 @@ FLASH_RESERVE_START_KB 64
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs (UART3RX used for RCInput, UART4RX and USART6RX not pinned out)
|
||||
UART_ORDER OTG1 USART2 USART1 UART5 EMPTY UART4 USART6
|
||||
SERIAL_ORDER OTG1 USART1 UART5 USART2 EMPTY UART4 USART6
|
||||
|
||||
# USB sensing
|
||||
#PA9 VBUS INPUT OPENDRAIN
|
||||
@ -151,7 +147,7 @@ define HAL_PROBE_EXTERNAL_I2C_BAROS
|
||||
#define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
# OSD support
|
||||
define OSD_ENABLED ENABLED
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
|
@ -6,11 +6,6 @@ MCU STM32F4xx STM32F407xx
|
||||
APJ_BOARD_ID 20
|
||||
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
STM32_ST_USE_TIMER 5
|
||||
|
||||
@ -18,7 +13,7 @@ STM32_ST_USE_TIMER 5
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2
|
||||
SERIAL_ORDER OTG1 USART2
|
||||
|
||||
PE3 LED_BOOTLOADER OUTPUT
|
||||
PE2 LED_ACTIVITY OUTPUT
|
||||
|
@ -6,8 +6,7 @@ MCU STM32F4xx STM32F407xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 20
|
||||
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_F4BY
|
||||
|
||||
|
||||
# USB setup
|
||||
USB_VENDOR 0x27AC # Swift-Flyer
|
||||
USB_PRODUCT 0x0201 # fmu usb driver
|
||||
@ -19,10 +18,6 @@ FLASH_SIZE_KB 1024
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# this is the STM32 timer that ChibiOS will use for the low level
|
||||
# driver. This must be a 32 bit timer. We currently only support
|
||||
@ -53,7 +48,7 @@ PA14 JTCK-SWCLK SWD
|
||||
# setup as OPENDRAIN
|
||||
PA9 VBUS INPUT OPENDRAIN
|
||||
|
||||
UART_ORDER OTG1 USART3 USART2 USART1 UART5
|
||||
SERIAL_ORDER OTG1 USART2 USART1 USART3 UART5
|
||||
|
||||
# UART1 as board 2.1.5 for serial 3 gps
|
||||
PB6 USART1_TX USART1
|
||||
@ -75,7 +70,6 @@ PC12 UART5_TX UART5 NODMA
|
||||
PD2 UART5_RX UART5 NODMA
|
||||
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
define STORAGE_FLASH_PAGE 22
|
||||
|
||||
#SPI1 for MPU
|
||||
PA5 SPI1_SCK SPI1
|
||||
|
@ -8,7 +8,6 @@ APJ_BOARD_ID 122
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
@ -22,11 +21,9 @@ define HAL_LED_ON 0
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -1,8 +1,6 @@
|
||||
# hw definition file for KakuteF4 hardware
|
||||
|
||||
# STATUS:
|
||||
# This port is mostly complete. Main missing feature are OSD,
|
||||
# dataflash
|
||||
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F4xx STM32F405xx
|
||||
@ -15,15 +13,12 @@ APJ_BOARD_ID 122
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
define STM32_ST_USE_TIMER 4
|
||||
define CH_CFG_ST_RESOLUTION 16
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# only one I2C bus
|
||||
I2C_ORDER I2C1
|
||||
@ -73,7 +68,7 @@ define HAL_BATT_VOLT_SCALE 10.1
|
||||
define HAL_BATT_CURR_SCALE 17.0
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART6 USART1 UART5 USART3
|
||||
SERIAL_ORDER OTG1 USART6 USART1 UART4 UART5 USART3
|
||||
|
||||
# rcinput is PB11
|
||||
PB11 TIM2_CH4 TIM2 RCININT FLOAT LOW
|
||||
@ -150,7 +145,7 @@ BARO BMP280 I2C:0:0x76
|
||||
define HAL_LOGGING_DATAFLASH
|
||||
|
||||
# setup for OSD
|
||||
define OSD_ENABLED ENABLED
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
|
@ -13,12 +13,6 @@ OSCILLATOR_HZ 8000000
|
||||
define STM32_LSECLK 32768U
|
||||
define STM32_LSEDRV (3U << 3U)
|
||||
|
||||
define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
define STM32_PLLM_VALUE 8
|
||||
define STM32_PLLN_VALUE 432
|
||||
define STM32_PLLP_VALUE 2
|
||||
define STM32_PLLQ_VALUE 9
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# bootloader starts at zero offset
|
||||
@ -27,11 +21,9 @@ FLASH_RESERVE_START_KB 0
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 96
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
# PA10 IO-debug-console
|
||||
PA11 OTG_FS_DM OTG1
|
||||
|
@ -11,28 +11,17 @@ APJ_BOARD_ID 123
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
define STM32_LSECLK 32768U
|
||||
define STM32_LSEDRV (3U << 3U)
|
||||
|
||||
define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
define STM32_PLLM_VALUE 8
|
||||
define STM32_PLLN_VALUE 432
|
||||
define STM32_PLLP_VALUE 2
|
||||
define STM32_PLLQ_VALUE 9
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# leave 2 sectors free
|
||||
FLASH_RESERVE_START_KB 96
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# only one I2C bus
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs (and USB), USART3 should be in second place to map order with the board's silk screen
|
||||
UART_ORDER OTG1 USART3 USART1 USART2 UART4 UART7 USART6
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART7 USART6
|
||||
|
||||
# buzzer
|
||||
PD15 TIM4_CH4 TIM4 GPIO(77) ALARM
|
||||
@ -99,9 +88,13 @@ PB10 USART3_TX USART3
|
||||
PA0 UART4_TX UART4 NODMA
|
||||
PA1 UART4_RX UART4 NODMA
|
||||
|
||||
# USART6, RX only for RCIN
|
||||
PC7 TIM8_CH2 TIM8 RCININT FLOAT LOW
|
||||
PC6 USART6_TX USART6 NODMA LOW
|
||||
# RC input defaults to timer capture
|
||||
PC7 TIM8_CH2 TIM8 RCININT PULLDOWN
|
||||
|
||||
# alternative config using USART for protocols
|
||||
# like FPort
|
||||
PC7 USART6_RX USART6 NODMA ALT(1)
|
||||
PC6 USART6_TX USART6 NODMA
|
||||
|
||||
# UART7 USED BY ESC FROM ORIGINAL DESIGN
|
||||
PE7 UART7_RX UART7
|
||||
@ -148,7 +141,7 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
# setup for OSD
|
||||
define OSD_ENABLED ENABLED
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
@ -157,3 +150,4 @@ define STM32_PWM_USE_ADVANCED TRUE
|
||||
|
||||
# we are low on flash on this board
|
||||
define HAL_MINIMIZE_FEATURES 1
|
||||
define HAL_WITH_DSP 1
|
||||
|
@ -11,28 +11,17 @@ APJ_BOARD_ID 145
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
define STM32_LSECLK 32768U
|
||||
define STM32_LSEDRV (3U << 3U)
|
||||
|
||||
define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
define STM32_PLLM_VALUE 8
|
||||
define STM32_PLLN_VALUE 432
|
||||
define STM32_PLLP_VALUE 2
|
||||
define STM32_PLLQ_VALUE 9
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# leave 2 sectors free
|
||||
FLASH_RESERVE_START_KB 96
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# only one I2C bus
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs (and USB), USART3 should be in second place to map order with the board's silk screen
|
||||
UART_ORDER OTG1 USART3 USART1 USART2 UART4 EMPTY USART6 UART7
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6 UART7
|
||||
|
||||
# buzzer
|
||||
PD15 TIM4_CH4 TIM4 GPIO(77) ALARM
|
||||
@ -99,9 +88,13 @@ PB10 USART3_TX USART3
|
||||
PA0 UART4_TX UART4 NODMA
|
||||
PA1 UART4_RX UART4 NODMA
|
||||
|
||||
# USART6, RX only for RCIN
|
||||
PC7 TIM8_CH2 TIM8 RCININT FLOAT LOW
|
||||
PC6 USART6_TX USART6 NODMA LOW
|
||||
# RC input defaults to timer capture
|
||||
PC7 TIM8_CH2 TIM8 RCININT PULLDOWN
|
||||
PC6 USART6_TX USART6 NODMA
|
||||
|
||||
# alt config to allow RCIN on UART for bi-directional
|
||||
# protocols like FPort
|
||||
PC7 USART6_RX USART6 NODMA ALT(1)
|
||||
|
||||
# UART7, RX only for ESC Telemetry
|
||||
PE7 UART7_RX UART7
|
||||
@ -147,10 +140,24 @@ IMU Invensense SPI:mpu6000 ROTATION_YAW_180
|
||||
BARO BMP280 I2C:0:0x76
|
||||
|
||||
# setup for OSD
|
||||
define OSD_ENABLED ENABLED
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
define BOARD_PWM_COUNT_DEFAULT 6
|
||||
define STM32_PWM_USE_ADVANCED TRUE
|
||||
|
||||
# disable SMBUS and fuel battery monitors to save flash
|
||||
define HAL_BATTMON_SMBUS_ENABLE 0
|
||||
define HAL_BATTMON_FUEL_ENABLE 0
|
||||
|
||||
# disable parachute and sprayer to save flash
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
define HAL_SPRAYER_ENABLED 0
|
||||
|
||||
# reduce max size of embedded params for apj_tool.py
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
|
||||
|
||||
# we are low on flash on this board
|
||||
define HAL_MINIMIZE_FEATURES 1
|
||||
define HAL_WITH_DSP 1
|
||||
|
@ -9,7 +9,6 @@ APJ_BOARD_ID 127
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
@ -22,11 +21,9 @@ FLASH_BOOTLOADER_LOAD_KB 64
|
||||
define HAL_STORAGE_SIZE 15360
|
||||
define STORAGE_FLASH_PAGE 1
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1 USART1 USART3 UART4 UART5 USART6
|
||||
SERIAL_ORDER OTG1 USART1 USART3 UART4 UART5 USART6
|
||||
|
||||
PA0 UART4_TX UART4
|
||||
PA1 UART4_RX UART4
|
||||
|
@ -22,14 +22,11 @@
|
||||
# MCU class and specific type
|
||||
MCU STM32F4xx STM32F405xx
|
||||
|
||||
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_MATEKF405WING
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 127
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
define STM32_ST_USE_TIMER 5
|
||||
define CH_CFG_ST_RESOLUTION 32
|
||||
@ -41,14 +38,12 @@ FLASH_SIZE_KB 1024
|
||||
define HAL_STORAGE_SIZE 15360
|
||||
define STORAGE_FLASH_PAGE 1
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# I2C Buses
|
||||
I2C_ORDER I2C1 I2C2
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1 USART3 USART1 EMPTY UART4 UART5 USART6
|
||||
SERIAL_ORDER OTG1 USART1 EMPTY USART3 UART4 UART5 USART6 USART2
|
||||
|
||||
#################################################
|
||||
### PIN DEFINITIONS ###
|
||||
@ -57,10 +52,12 @@ UART_ORDER OTG1 USART3 USART1 EMPTY UART4 UART5 USART6
|
||||
PA0 UART4_TX UART4
|
||||
PA1 UART4_RX UART4
|
||||
|
||||
# USART 2 is used for RC Input
|
||||
# PA2 USART2_TX USART2
|
||||
# PA3 USART2_RX USART2
|
||||
PA3 TIM2_CH4 TIM2 RCININT FLOAT LOW
|
||||
# default to timer for RC input
|
||||
PA3 TIM9_CH2 TIM9 RCININT FLOAT LOW
|
||||
|
||||
# alternative using USART2
|
||||
PA2 USART2_TX USART2 NODMA
|
||||
PA3 USART2_RX USART2 NODMA ALT(1)
|
||||
|
||||
PA4 MPU_CS CS
|
||||
|
||||
@ -92,6 +89,8 @@ PC9 TIM8_CH4 TIM8 PWM(6) GPIO(55)
|
||||
PB14 TIM1_CH2N TIM1 PWM(7) GPIO(56)
|
||||
PB15 TIM1_CH3N TIM1 PWM(8) GPIO(57)
|
||||
PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58)
|
||||
PA15 TIM2_CH1 TIM2 PWM(10) GPIO(59) #on LED pin,allows odd motor groups
|
||||
|
||||
|
||||
# SD CARD SPI
|
||||
PB3 SPI3_SCK SPI3
|
||||
@ -174,14 +173,22 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
define HAL_I2C_INTERNAL_MASK 0
|
||||
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
||||
|
||||
define OSD_ENABLED ENABLED
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
define BOARD_PWM_COUNT_DEFAULT 9
|
||||
define BOARD_PWM_COUNT_DEFAULT 10
|
||||
|
||||
define STM32_PWM_USE_ADVANCED TRUE
|
||||
|
||||
# disable SMBUS and fuel battery monitors to save flash
|
||||
define HAL_BATTMON_SMBUS_ENABLE 0
|
||||
define HAL_BATTMON_FUEL_ENABLE 0
|
||||
|
||||
# disable parachute and sprayer to save flash
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
define HAL_SPRAYER_ENABLED 0
|
||||
|
||||
# reduce max size of embedded params for apj_tool.py
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
|
||||
define HAL_WITH_DSP FALSE
|
||||
|
@ -9,7 +9,6 @@ APJ_BOARD_ID 125
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
@ -24,11 +23,9 @@ define HAL_LED_ON 0
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -2,9 +2,6 @@
|
||||
# tested on the MatekF405-OSD board
|
||||
# with thanks to betaflight for pinout
|
||||
|
||||
# STATUS:
|
||||
# This port is mostly complete. Main missing feature are OSD,
|
||||
# dataflash
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F4xx STM32F405xx
|
||||
@ -14,21 +11,18 @@ APJ_BOARD_ID 125
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
define STM32_ST_USE_TIMER 4
|
||||
define CH_CFG_ST_RESOLUTION 16
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# only one I2C bus
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART3 UART4 UART5
|
||||
SERIAL_ORDER OTG1 USART3 UART4 USART1 UART5 USART2
|
||||
|
||||
# LEDs
|
||||
PB9 LED_BLUE OUTPUT LOW GPIO(0)
|
||||
@ -88,12 +82,12 @@ define BOARD_RSSI_ANA_PIN 9
|
||||
PA9 USART1_TX USART1
|
||||
PA10 USART1_RX USART1
|
||||
|
||||
# USART2 (RCIN)
|
||||
#PA2 USART3_TX USART3
|
||||
#PA3 USART3_RX USART3
|
||||
# RC input using timer
|
||||
PA3 TIM9_CH2 TIM9 RCININT PULLDOWN
|
||||
|
||||
# rcinput
|
||||
PA3 TIM9_CH2 TIM9 RCININT FLOAT LOW
|
||||
# alternative RC input using UART
|
||||
PA2 USART2_TX USART2 NODMA
|
||||
PA3 USART2_RX USART2 NODMA ALT(1)
|
||||
|
||||
# USART3
|
||||
PC10 USART3_TX USART3
|
||||
@ -162,14 +156,18 @@ define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
# 8 PWM available by default
|
||||
define BOARD_PWM_COUNT_DEFAULT 8
|
||||
|
||||
# uncomment the lines below to enable strict API
|
||||
# checking in ChibiOS
|
||||
#define CH_DBG_ENABLE_ASSERTS TRUE
|
||||
#define CH_DBG_ENABLE_CHECKS TRUE
|
||||
#define CH_DBG_SYSTEM_STATE_CHECK TRUE
|
||||
#define CH_DBG_ENABLE_STACK_CHECK TRUE
|
||||
|
||||
# setup for OSD
|
||||
define OSD_ENABLED ENABLED
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
# disable SMBUS and fuel battery monitors to save flash
|
||||
define HAL_BATTMON_SMBUS_ENABLE 0
|
||||
define HAL_BATTMON_FUEL_ENABLE 0
|
||||
|
||||
# disable parachute and sprayer to save flash
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
define HAL_SPRAYER_ENABLED 0
|
||||
|
||||
# reduce max size of embedded params for apj_tool.py
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
|
||||
|
@ -10,15 +10,6 @@ APJ_BOARD_ID 143
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
define STM32_LSECLK 32768U
|
||||
define STM32_LSEDRV (3U << 3U)
|
||||
|
||||
define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
define STM32_PLLM_VALUE 8
|
||||
define STM32_PLLN_VALUE 432
|
||||
define STM32_PLLP_VALUE 2
|
||||
define STM32_PLLQ_VALUE 9
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader starts at zero offset
|
||||
@ -27,11 +18,9 @@ FLASH_RESERVE_START_KB 0
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 96
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs (and USB). Allow bootloading on USB and telem1
|
||||
UART_ORDER OTG1 UART7
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 (telem1)
|
||||
PE7 UART7_RX UART7
|
||||
|
@ -10,22 +10,11 @@ APJ_BOARD_ID 143
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
define STM32_LSECLK 32768U
|
||||
define STM32_LSEDRV (3U << 3U)
|
||||
|
||||
define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
define STM32_PLLM_VALUE 8
|
||||
define STM32_PLLN_VALUE 432
|
||||
define STM32_PLLP_VALUE 2
|
||||
define STM32_PLLQ_VALUE 9
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# leave 2 sectors free
|
||||
FLASH_RESERVE_START_KB 96
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
STM32_ST_USE_TIMER 12
|
||||
define CH_CFG_ST_RESOLUTION 16
|
||||
@ -34,7 +23,7 @@ define CH_CFG_ST_RESOLUTION 16
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2 UART7 USART1 USART3 UART8 UART4
|
||||
SERIAL_ORDER OTG1 UART7 USART1 USART2 USART3 UART8 UART4 USART6
|
||||
|
||||
# tonealarm support
|
||||
PB9 TIM11_CH1 TIM11 GPIO(32) ALARM
|
||||
@ -122,9 +111,14 @@ PD0 UART4_RX UART4 NODMA
|
||||
# UART5 (RX only, for ESC telem), disabled for now until we add uartH support
|
||||
# PB8 UART5_RX UART5 NODMA
|
||||
|
||||
# USART6 (RC input)
|
||||
# USART6 (RC input), SERIAL7
|
||||
PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW
|
||||
PC6 USART6_TX USART6 NODMA LOW
|
||||
PC6 USART6_TX USART6 NODMA
|
||||
|
||||
# as an alternative config setup the RX6 pin as a uart. This allows
|
||||
# for bi-directional UART based receiver protocols such as FPort
|
||||
# without any extra hardware
|
||||
PC7 USART6_RX USART6 NODMA ALT(1)
|
||||
|
||||
# UART7 (telem1)
|
||||
PE7 UART7_RX UART7
|
||||
@ -201,7 +195,7 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
# setup for OSD
|
||||
define OSD_ENABLED ENABLED
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
|
50
libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef-bl.dat
Normal file
50
libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef-bl.dat
Normal file
@ -0,0 +1,50 @@
|
||||
# hw definition file for processing by chibios_pins.py
|
||||
# for Matek H743-WING bootloader
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1013
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader starts at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# reserve space for flash storage in last 2 sectors
|
||||
FLASH_RESERVE_END_KB 256
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
# the H743 has 128k sectors
|
||||
FLASH_BOOTLOADER_LOAD_KB 128
|
||||
|
||||
|
||||
# order of UARTs (and USB). Allow bootloading on USB and telem1
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 (telem1)
|
||||
PE7 UART7_RX UART7 NODMA
|
||||
PE8 UART7_TX UART7 NODMA
|
||||
|
||||
# PA10 IO-debug-console
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
PE3 LED_BOOTLOADER OUTPUT LOW
|
||||
define HAL_LED_ON 0
|
||||
|
||||
define HAL_USE_EMPTY_STORAGE 1
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PC15 IMU1_CS CS
|
||||
PB12 MAX7456_CS CS
|
||||
PD4 MS5611_CS CS
|
||||
PE11 IMU2_CS CS
|
210
libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat
Normal file
210
libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat
Normal file
@ -0,0 +1,210 @@
|
||||
# hw definition file for processing by chibios_pins.py
|
||||
# for Matek H743-WING
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1013
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# bootloader takes first sector
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 12
|
||||
define CH_CFG_ST_RESOLUTION 16
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# SPI1 for IMU1 (MPU6000)
|
||||
PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PD7 SPI1_MOSI SPI1
|
||||
PC15 IMU1_CS CS
|
||||
|
||||
# SPI2 for MAX7456 OSD
|
||||
PB12 MAX7456_CS CS
|
||||
PB13 SPI2_SCK SPI2
|
||||
PB14 SPI2_MISO SPI2
|
||||
PB15 SPI2_MOSI SPI2
|
||||
|
||||
# SPI3 for MS5611
|
||||
PD4 MS5611_CS CS
|
||||
PB3 SPI3_SCK SPI3
|
||||
PB4 SPI3_MISO SPI3
|
||||
PB5 SPI3_MOSI SPI3
|
||||
|
||||
# SPI4 for IMU2 (ICM20602)
|
||||
PE11 IMU2_CS CS
|
||||
PE12 SPI4_SCK SPI4
|
||||
PE13 SPI4_MISO SPI4
|
||||
PE14 SPI4_MOSI SPI4
|
||||
|
||||
# two I2C bus
|
||||
I2C_ORDER I2C1 I2C2
|
||||
|
||||
# I2C1
|
||||
PB6 I2C1_SCL I2C1
|
||||
PB7 I2C1_SDA I2C1
|
||||
|
||||
# I2C2
|
||||
PB10 I2C2_SCL I2C2
|
||||
PB11 I2C2_SDA I2C2
|
||||
|
||||
# ADC
|
||||
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
PA4 BATT2_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PA7 BATT2_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
define HAL_BATT_MONITOR_DEFAULT 4
|
||||
define HAL_BATT_VOLT_PIN 10
|
||||
define HAL_BATT_CURR_PIN 11
|
||||
define HAL_BATT2_VOLT_PIN 18
|
||||
define HAL_BATT2_CURR_PIN 7
|
||||
define HAL_BATT_VOLT_SCALE 11.0
|
||||
define HAL_BATT_CURR_SCALE 40.0
|
||||
define HAL_BATT2_VOLT_SCALE 11.0
|
||||
|
||||
PC4 PRESSURE_SENS ADC1 SCALE(2)
|
||||
define HAL_DEFAULT_AIRSPEED_PIN 4
|
||||
|
||||
PC5 RSSI_ADC ADC1
|
||||
define BOARD_RSSI_ANA_PIN 8
|
||||
|
||||
# LED
|
||||
# green LED1 marked as B/E
|
||||
# blue LED0 marked as ACT
|
||||
PE3 LED0 OUTPUT LOW GPIO(90) # blue
|
||||
PE4 LED1 OUTPUT LOW GPIO(91) # green
|
||||
define HAL_GPIO_A_LED_PIN 91
|
||||
define HAL_GPIO_B_LED_PIN 90
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 UART7 USART1 USART2 USART3 UART8 UART4 USART6
|
||||
|
||||
# USART1 (telem2)
|
||||
PA10 USART1_RX USART1
|
||||
PA9 USART1_TX USART1
|
||||
|
||||
# USART2 (GPS1)
|
||||
PD5 USART2_TX USART2
|
||||
PD6 USART2_RX USART2
|
||||
|
||||
# USART3 (GPS2)
|
||||
PD9 USART3_RX USART3
|
||||
PD8 USART3_TX USART3
|
||||
|
||||
# UART4 (spare)
|
||||
PB9 UART4_TX UART4
|
||||
PB8 UART4_RX UART4
|
||||
|
||||
# USART6 (RC input), SERIAL7
|
||||
PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW
|
||||
PC6 USART6_TX USART6 NODMA
|
||||
|
||||
# as an alternative config setup the RX6 pin as a uart. This allows
|
||||
# for bi-directional UART based receiver protocols such as FPort
|
||||
# without any extra hardware
|
||||
PC7 USART6_RX USART6 NODMA ALT(1)
|
||||
|
||||
# UART7 (telem1)
|
||||
PE7 UART7_RX UART7
|
||||
PE8 UART7_TX UART7
|
||||
PE10 UART7_CTS UART7
|
||||
PE9 UART7_RTS UART7
|
||||
|
||||
# UART8 (spare)
|
||||
PE0 UART8_RX UART8
|
||||
PE1 UART8_TX UART8
|
||||
|
||||
# CAN bus
|
||||
PD0 CAN1_RX CAN1
|
||||
PD1 CAN1_TX CAN1
|
||||
PD3 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)
|
||||
|
||||
# Motors
|
||||
PB0 TIM8_CH2N TIM8 PWM(1) GPIO(50)
|
||||
PB1 TIM8_CH3N TIM8 PWM(2) GPIO(51)
|
||||
PA0 TIM5_CH1 TIM5 PWM(3) GPIO(52)
|
||||
PA1 TIM5_CH2 TIM5 PWM(4) GPIO(53)
|
||||
PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54)
|
||||
PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55)
|
||||
PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56)
|
||||
PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57)
|
||||
PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58)
|
||||
PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59)
|
||||
PE5 TIM15_CH1 TIM15 PWM(11) GPIO(60)
|
||||
PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61)
|
||||
PA8 TIM1_CH1 TIM1 PWM(13) GPIO(62) # for WS2812 LED
|
||||
|
||||
# Beeper
|
||||
PA15 TIM2_CH1 TIM2 GPIO(32) ALARM
|
||||
|
||||
# microSD support
|
||||
PC8 SDMMC1_D0 SDMMC1
|
||||
PC9 SDMMC1_D1 SDMMC1
|
||||
PC10 SDMMC1_D2 SDMMC1
|
||||
PC11 SDMMC1_D3 SDMMC1
|
||||
PC12 SDMMC1_CK SDMMC1
|
||||
PD2 SDMMC1_CMD SDMMC1
|
||||
|
||||
# GPIOs
|
||||
PD10 PINIO1 OUTPUT GPIO(81) LOW
|
||||
PD11 PINIO2 OUTPUT GPIO(82) LOW
|
||||
|
||||
DMA_PRIORITY S*
|
||||
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
# use last 2 pages for flash storage
|
||||
# H743 has 16 pages of 128k each
|
||||
define STORAGE_FLASH_PAGE 14
|
||||
|
||||
# spi devices
|
||||
SPIDEV ms5611 SPI3 DEVID1 MS5611_CS MODE3 20*MHZ 20*MHZ
|
||||
SPIDEV mpu6000 SPI1 DEVID1 IMU1_CS MODE3 1*MHZ 4*MHZ
|
||||
SPIDEV icm20602 SPI4 DEVID1 IMU2_CS MODE3 1*MHZ 4*MHZ
|
||||
SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ
|
||||
|
||||
# no built-in compass, but probe the i2c bus for all possible
|
||||
# external compass types
|
||||
define ALLOW_ARM_NO_COMPASS
|
||||
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
define HAL_I2C_INTERNAL_MASK 1
|
||||
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
||||
|
||||
# two IMUs. We put icm20602 first as we can sample accel at 4kHz
|
||||
IMU Invensense SPI:icm20602 ROTATION_ROLL_180_YAW_270
|
||||
IMU Invensense SPI:mpu6000 ROTATION_ROLL_180_YAW_270
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 1
|
||||
|
||||
# one BARO
|
||||
BARO MS56XX SPI:ms5611
|
||||
|
||||
define HAL_OS_FATFS_IO 1
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
# setup for OSD
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
define BOARD_PWM_COUNT_DEFAULT 13
|
||||
|
||||
|
@ -22,11 +22,9 @@ FLASH_RESERVE_START_KB 0
|
||||
# the H743 has 128k sectors
|
||||
FLASH_BOOTLOADER_LOAD_KB 128
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
# UART7 is debug
|
||||
PF6 UART7_RX UART7 NODMA
|
||||
|
@ -17,11 +17,9 @@ FLASH_SIZE_KB 2048
|
||||
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART7
|
||||
SERIAL_ORDER OTG1 EMPTY EMPTY UART7
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -10,15 +10,6 @@ APJ_BOARD_ID 121
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
define STM32_LSECLK 32768U
|
||||
define STM32_LSEDRV (3U << 3U)
|
||||
|
||||
define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
define STM32_PLLM_VALUE 8
|
||||
define STM32_PLLN_VALUE 432
|
||||
define STM32_PLLP_VALUE 2
|
||||
define STM32_PLLQ_VALUE 9
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
@ -27,10 +18,8 @@ FLASH_RESERVE_START_KB 0
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 96
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
# PA10 IO-debug-console
|
||||
PA11 OTG_FS_DM OTG1
|
||||
|
@ -5,36 +5,23 @@
|
||||
# MCU class and specific type
|
||||
MCU STM32F7xx STM32F745xx
|
||||
|
||||
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_OMNIBUSF7V2
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 121
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
define STM32_LSECLK 32768U
|
||||
define STM32_LSEDRV (3U << 3U)
|
||||
|
||||
define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
define STM32_PLLM_VALUE 8
|
||||
define STM32_PLLN_VALUE 432
|
||||
define STM32_PLLP_VALUE 2
|
||||
define STM32_PLLQ_VALUE 9
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# reserve one sector for bootloader and 2 for storage
|
||||
FLASH_RESERVE_START_KB 96
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# only one I2C bus
|
||||
I2C_ORDER I2C2
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART6 USART1 USART3
|
||||
SERIAL_ORDER OTG1 USART1 USART3 USART6 USART2
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
@ -94,8 +81,11 @@ IMU Invensense SPI:mpu6500 ROTATION_YAW_90
|
||||
PA10 USART1_RX USART1
|
||||
PA9 USART1_TX USART1
|
||||
|
||||
# USART2 for RC input, RX only
|
||||
PA3 TIM9_CH2 TIM9 RCININT FLOAT LOW
|
||||
# RC input using timer by default
|
||||
PA3 TIM9_CH2 TIM9 RCININT PULLDOWN
|
||||
|
||||
# alternative RC input using USART2
|
||||
PA3 USART2_RX USART2 NODMA ALT(1)
|
||||
|
||||
# USART3
|
||||
PD9 USART3_RX USART3
|
||||
@ -138,7 +128,7 @@ define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
||||
# one baro
|
||||
BARO BMP280 SPI:bmp280
|
||||
|
||||
define OSD_ENABLED ENABLED
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
|
@ -9,7 +9,6 @@ APJ_BOARD_ID 133
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
@ -26,11 +25,9 @@ define HAL_LED_ON 0
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -9,10 +9,6 @@ APJ_BOARD_ID 133
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
STM32_ST_USE_TIMER 5
|
||||
|
||||
@ -24,7 +20,7 @@ FLASH_RESERVE_START_KB 64
|
||||
I2C_ORDER I2C2
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1 USART6 USART1 UART4
|
||||
SERIAL_ORDER OTG1 USART1 UART4 USART6
|
||||
|
||||
#adc
|
||||
PC1 BAT_CURR_SENS ADC1 SCALE(1)
|
||||
@ -104,8 +100,6 @@ SPIDEV dataflash SPI2 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ
|
||||
# enable logging to dataflash
|
||||
define HAL_LOGGING_DATAFLASH
|
||||
|
||||
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_OMNIBUSNANOV6
|
||||
|
||||
# one IMU
|
||||
IMU Invensense SPI:mpu6000 ROTATION_YAW_90
|
||||
|
||||
@ -136,7 +130,7 @@ define BOARD_RSSI_ANA_PIN 0
|
||||
|
||||
define HAL_GPIO_A_LED_PIN 41
|
||||
|
||||
define OSD_ENABLED ENABLED
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
|
||||
#To complementary channels work we define this
|
||||
@ -144,10 +138,5 @@ define STM32_PWM_USE_ADVANCED TRUE
|
||||
|
||||
define BOARD_PWM_COUNT_DEFAULT 4
|
||||
|
||||
#define CH_DBG_ENABLE_ASSERTS TRUE
|
||||
#define CH_DBG_ENABLE_CHECKS TRUE
|
||||
#define CH_DBG_SYSTEM_STATE_CHECK TRUE
|
||||
#define CH_DBG_ENABLE_STACK_CHECK TRUE
|
||||
|
||||
#font for the osd
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
@ -9,7 +9,7 @@ include ../fmuv5/hwdef.dat
|
||||
STM32_ST_USE_TIMER 5
|
||||
|
||||
# order of UARTs (and USB). Telem2 is UART4 on the mini, USART3 is not available
|
||||
UART_ORDER OTG1 USART1 USART2 UART4 USART6 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 UART4 USART1 USART6 UART7 OTG2
|
||||
|
||||
# enable TX on USART6 (disabled for fmuv5 with iomcu)
|
||||
PG14 USART6_TX USART6 NODMA
|
||||
|
@ -5,3 +5,4 @@ include ../Pixhawk1/hwdef.dat
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
define HAL_MINIMIZE_FEATURES 1
|
||||
undef STORAGE_FLASH_PAGE
|
||||
|
@ -10,7 +10,7 @@ The Pixhawk4 flight controller is sold by [Holybro](http://www.holybro.com/produ
|
||||
- builtin I2C IST8310 magnetometer
|
||||
- microSD card slot
|
||||
- 6 UARTs plus USB
|
||||
- 14 PWM outputs
|
||||
- 16 PWM outputs
|
||||
- Four I2C and two CAN ports
|
||||
- External Buzzer
|
||||
- external safety Switch
|
||||
@ -27,7 +27,7 @@ The Pixhawk4 flight controller is sold by [Holybro](http://www.holybro.com/produ
|
||||
- SERIAL1 -> UART2 (Telem1)
|
||||
- SERIAL2 -> UART3 (Telem2)
|
||||
- SERIAL3 -> UART1 (GPS)
|
||||
- SERIAL4 -> UART4 (GPS2)
|
||||
- SERIAL4 -> UART4 (GPS2, marked UART/I2CB)
|
||||
- SERIAL5 -> UART6 (spare)
|
||||
- SERIAL6 -> UART7 (spare, debug)
|
||||
|
||||
@ -157,7 +157,7 @@ outputs support all PWM output formats, but not DShot.
|
||||
|
||||
The remaining 8 outputs (labelled AUX1 to AUX8) are the "auxillary"
|
||||
outputs. These are directly attached to the STM32F765 and support all
|
||||
PWM protocols. The first 6 of the auxillary PWM outputs support DShot.
|
||||
PWM protocols. The first 4 of the auxillary PWM outputs support DShot.
|
||||
|
||||
The 8 main PWM outputs are in 3 groups:
|
||||
|
||||
@ -165,7 +165,7 @@ The 8 main PWM outputs are in 3 groups:
|
||||
- PWM 3 and 4 in group2
|
||||
- PWM 5, 6, 7 and 8 in group3
|
||||
|
||||
The 8 auxillary PWM outputs are in 2 groups:
|
||||
The 8 auxillary PWM outputs are in 3 groups:
|
||||
|
||||
- PWM 1, 2, 3 and 4 in group1
|
||||
- PWM 5 and 6 in group2
|
||||
|
44
libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef-bl.dat
Normal file
44
libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef-bl.dat
Normal file
@ -0,0 +1,44 @@
|
||||
# hw definition file for processing by chibios_pins.py
|
||||
# for FrSky R9Pilot bootloader
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F7xx STM32F767xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1008
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader starts at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 96
|
||||
|
||||
|
||||
# order of UARTs (and USB). Allow bootloading on USB
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
# PA10 IO-debug-console
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
PE0 LED_BOOTLOADER OUTPUT LOW
|
||||
define HAL_LED_ON 0
|
||||
|
||||
define HAL_USE_EMPTY_STORAGE 1
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PA4 BARO_CS CS
|
||||
PA1 BARO_CS2 CS
|
||||
PB12 EXT_CS CS
|
||||
PA15 IMU_CS CS
|
||||
PE4 SDCARD_CS CS
|
184
libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef.dat
Normal file
184
libraries/AP_HAL_ChibiOS/hwdef/R9Pilot/hwdef.dat
Normal file
@ -0,0 +1,184 @@
|
||||
# hw definition file for processing by chibios_pins.py
|
||||
# for FrSky R9Pilot
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F7xx STM32F767xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1008
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# leave 2 sectors free
|
||||
FLASH_RESERVE_START_KB 96
|
||||
|
||||
|
||||
# one I2C bus (I2C2 can be used with loss of USART3)
|
||||
I2C_ORDER I2C3
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART2 USART3 USART1 UART5 USART6 UART7 UART8
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
PC4 VBUS INPUT OPENDRAIN
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# SPI1 for baro
|
||||
PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
PA4 BARO_CS CS
|
||||
PA1 BARO_CS2 CS
|
||||
|
||||
# SPI2 external (gyro box, 7 pin ribbon cable)
|
||||
PB13 SPI2_SCK SPI2
|
||||
PB14 SPI2_MISO SPI2
|
||||
PB15 SPI2_MOSI SPI2
|
||||
PB12 EXT_CS CS
|
||||
|
||||
# SPI3 for on-board IMU
|
||||
PC10 SPI3_SCK SPI3
|
||||
PC11 SPI3_MISO SPI3
|
||||
PC12 SPI3_MOSI SPI3
|
||||
PA15 IMU_CS CS
|
||||
PE8 MPU3_INT INPUT
|
||||
|
||||
# SPI4 for microSD
|
||||
PE4 SDCARD_CS CS
|
||||
PE2 SPI4_SCK SPI4
|
||||
PE5 SPI4_MISO SPI4
|
||||
PE6 SPI4_MOSI SPI4
|
||||
|
||||
# I2C3
|
||||
PA8 I2C3_SCL I2C3
|
||||
PC9 I2C3_SDA I2C3
|
||||
|
||||
# I2C2 (if not USART3)
|
||||
# PB10 I2C2_SCL I2C2
|
||||
# PB11 I2C2_SDA I2C2
|
||||
|
||||
# USART1 for GPS
|
||||
PA10 USART1_RX USART1
|
||||
PA9 USART1_TX USART1
|
||||
|
||||
# USART2 for telem1
|
||||
PD5 USART2_TX USART2
|
||||
PD6 USART2_RX USART2
|
||||
|
||||
# USART3 for telem2
|
||||
PB11 USART3_RX USART3
|
||||
PB10 USART3_TX USART3
|
||||
|
||||
# UART5 spare uart
|
||||
PB5 UART5_RX UART5
|
||||
PB6 UART5_TX UART5
|
||||
|
||||
# USART6, Pixel OSD
|
||||
PC7 USART6_RX USART6
|
||||
PC6 USART6_TX USART6
|
||||
|
||||
# UART7, used for SBUS input
|
||||
PB3 UART7_RX UART7
|
||||
PB4 UART7_TX UART7
|
||||
|
||||
# alternatively use UART7 RX for RCInput using timer
|
||||
PB3 TIM2_CH2 TIM2 RCININT PULLDOWN LOW ALT(1)
|
||||
|
||||
# UART8, marked "RX RFD", connected to RXSR receiver via
|
||||
# 7-pin ribbon cable
|
||||
PE1 UART8_TX UART8 NODMA
|
||||
|
||||
PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
# define default battery setup
|
||||
define HAL_BATT_VOLT_PIN 13
|
||||
define HAL_BATT_CURR_PIN 12
|
||||
define HAL_BATT_VOLT_SCALE 10.1
|
||||
define HAL_BATT_CURR_SCALE 17.0
|
||||
|
||||
# analog RSSI
|
||||
PC5 RSSI_ADC ADC1
|
||||
define BOARD_RSSI_ANA_PIN 15
|
||||
|
||||
# analog pitot option (not on prototype boards)
|
||||
PC0 PRESSURE_SENS ADC1 SCALE(2)
|
||||
define HAL_DEFAULT_AIRSPEED_PIN 10
|
||||
|
||||
PE0 LED0 OUTPUT LOW GPIO(90) # blue
|
||||
PA3 LED1 OUTPUT LOW GPIO(91) # green
|
||||
define HAL_GPIO_A_LED_PIN 91
|
||||
define HAL_GPIO_B_LED_PIN 90
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
||||
# PWM outputs
|
||||
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50)
|
||||
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51)
|
||||
PE9 TIM1_CH1 TIM1 PWM(3) GPIO(52)
|
||||
PE11 TIM1_CH2 TIM1 PWM(4) GPIO(53)
|
||||
PE14 TIM1_CH4 TIM1 PWM(5) GPIO(54)
|
||||
PB7 TIM4_CH2 TIM4 PWM(6) GPIO(55)
|
||||
PB8 TIM4_CH3 TIM4 PWM(7) GPIO(56)
|
||||
PB9 TIM4_CH4 TIM4 PWM(8) GPIO(57)
|
||||
|
||||
# tonealarm support
|
||||
PA0 TIM5_CH1 TIM5 GPIO(32) ALARM
|
||||
|
||||
# GPIOs
|
||||
PE3 SD_DETECT INPUT
|
||||
|
||||
# switch1
|
||||
PC8 SW1 GPIO(70)
|
||||
|
||||
DMA_PRIORITY SPI* ADC*
|
||||
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
define STORAGE_FLASH_PAGE 1
|
||||
|
||||
# spi devices
|
||||
SPIDEV icm20602 SPI3 DEVID1 IMU_CS MODE3 1*MHZ 8*MHZ
|
||||
SPIDEV spl06 SPI1 DEVID1 BARO_CS MODE3 1*MHZ 1*MHZ
|
||||
SPIDEV imu2 SPI2 DEVID1 EXT_CS MODE3 1*MHZ 8*MHZ
|
||||
SPIDEV sdcard SPI4 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
|
||||
|
||||
# no built-in compass, but probe the i2c bus for all possible
|
||||
# external compass types
|
||||
define ALLOW_ARM_NO_COMPASS
|
||||
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
define HAL_I2C_INTERNAL_MASK 0
|
||||
|
||||
# one main IMU
|
||||
IMU Invensense SPI:icm20602 ROTATION_PITCH_180_YAW_90
|
||||
|
||||
# optional 2nd IMU, support any invensense part, board
|
||||
# may come with a ICM20601 IMU in a plastic case, called
|
||||
# "gyro box"
|
||||
IMU Invensense SPI:imu2 ROTATION_YAW_90
|
||||
|
||||
# also support newer Invensense IMUs
|
||||
IMU Invensensev2 SPI:imu2 ROTATION_YAW_90
|
||||
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 3
|
||||
|
||||
# one BARO, multiple possible choices for different
|
||||
# board varients
|
||||
BARO SPL06 SPI:spl06
|
||||
|
||||
# dummy for testing
|
||||
# BARO Dummy
|
||||
|
||||
# FAT filesystem on microSD
|
||||
define HAL_OS_FATFS_IO 1
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
define BOARD_PWM_COUNT_DEFAULT 8
|
||||
|
43
libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef-bl.dat
Normal file
43
libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef-bl.dat
Normal file
@ -0,0 +1,43 @@
|
||||
# hw definition file for processing by chibios_pins.py
|
||||
# for SuccexF4 bootloader
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F4xx STM32F405xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1011
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# don't allow bootloader to use more than 16k
|
||||
FLASH_USE_MAX_KB 16
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# LEDs
|
||||
PB5 LED_BOOTLOADER OUTPUT LOW
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
|
||||
# order of UARTs
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
define HAL_USE_EMPTY_STORAGE 1
|
||||
define HAL_STORAGE_SIZE 15360
|
||||
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PA4 ICM20689_1_CS CS
|
||||
PC3 ICM20689_2_CS CS
|
||||
PB12 AT7456E_CS CS
|
||||
PA15 FLASH_CS CS
|
136
libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat
Normal file
136
libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat
Normal file
@ -0,0 +1,136 @@
|
||||
# hw definition file for processing by chibios_pins.py
|
||||
# SuccexF4
|
||||
|
||||
MCU STM32F4xx STM32F405xx
|
||||
|
||||
HAL_CHIBIOS_ARCH_F405 1
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1011
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
STM32_ST_USE_TIMER 5
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 1024
|
||||
FLASH_RESERVE_START_KB 64
|
||||
|
||||
# ADC
|
||||
PC1 BAT_CURR_SENS ADC1 SCALE(1)
|
||||
PC2 BAT_VOLT_SENS ADC1 SCALE(1)
|
||||
|
||||
# PWM outputs
|
||||
PB0 TIM1_CH2N TIM1 PWM(1) GPIO(50)
|
||||
PB1 TIM1_CH3N TIM1 PWM(2) GPIO(51)
|
||||
PC9 TIM8_CH4 TIM8 PWM(3) GPIO(52)
|
||||
PC8 TIM8_CH3 TIM8 PWM(4) GPIO(53)
|
||||
|
||||
# Two IMUs on SPI1
|
||||
PC4 ICM20689_1_DRDY INPUT
|
||||
PA8 ICM20689_2_DRDY INPUT
|
||||
PA4 ICM20689_1_CS CS
|
||||
PC3 ICM20689_2_CS CS
|
||||
PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
|
||||
# OSD on SPI2
|
||||
PB12 AT7456E_CS CS
|
||||
PB13 SPI2_SCK SPI2
|
||||
PB14 SPI2_MISO SPI2
|
||||
PB15 SPI2_MOSI SPI2
|
||||
|
||||
# FLASH on SPI3
|
||||
PA15 FLASH_CS CS
|
||||
PC10 SPI3_SCK SPI3
|
||||
PC11 SPI3_MISO SPI3
|
||||
PC12 SPI3_MOSI SPI3
|
||||
|
||||
# Order of I2C buses
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# UART ports and I2C bus
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 USART6
|
||||
|
||||
# Note that this board needs pull-ups on I2C pins
|
||||
PB8 I2C1_SCL I2C1 PULLUP
|
||||
PB9 I2C1_SDA I2C1 PULLUP
|
||||
|
||||
PA10 USART1_RX USART1
|
||||
PA9 USART1_TX USART1
|
||||
|
||||
PA3 USART2_RX USART2
|
||||
PA2 USART2_TX USART2
|
||||
|
||||
PB11 USART3_RX USART3
|
||||
PB10 USART3_TX USART3
|
||||
|
||||
PC7 USART6_RX USART6
|
||||
PC6 USART6_TX USART6
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# LED and buzzer
|
||||
PB4 TIM3_CH1 TIM3 GPIO(56) ALARM
|
||||
PB5 LED OUTPUT HIGH GPIO(57)
|
||||
define HAL_GPIO_A_LED_PIN 57
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
PC5 VBUS INPUT OPENDRAIN
|
||||
|
||||
# LED strip pad as RC input
|
||||
PB6 TIM4_CH1 TIM4 RCININT PULLDOWN LOW
|
||||
|
||||
# SPI Device table
|
||||
SPIDEV icm20689_1 SPI1 DEVID1 ICM20689_1_CS MODE3 1*MHZ 8*MHZ
|
||||
SPIDEV icm20689_2 SPI1 DEVID2 ICM20689_2_CS MODE3 1*MHZ 8*MHZ
|
||||
SPIDEV osd SPI2 DEVID3 AT7456E_CS MODE0 10*MHZ 10*MHZ
|
||||
SPIDEV dataflash SPI3 DEVID4 FLASH_CS MODE3 32*MHZ 32*MHZ
|
||||
|
||||
# Two IMUs
|
||||
IMU Invensense SPI:icm20689_1 ROTATION_YAW_270
|
||||
IMU Invensense SPI:icm20689_2 ROTATION_NONE
|
||||
|
||||
# one baro
|
||||
BARO BMP280 I2C:0:0x76
|
||||
define HAL_PROBE_EXTERNAL_I2C_BAROS
|
||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||
|
||||
# no built-in compass, but probe the i2c bus for all possible
|
||||
# external compass types
|
||||
define ALLOW_ARM_NO_COMPASS
|
||||
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
define HAL_I2C_INTERNAL_MASK 0
|
||||
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
||||
|
||||
define STORAGE_FLASH_PAGE 1
|
||||
define HAL_STORAGE_SIZE 15360
|
||||
|
||||
# enable logging to dataflash
|
||||
define HAL_LOGGING_DATAFLASH
|
||||
|
||||
# define default battery setup
|
||||
define HAL_BATT_VOLT_PIN 12
|
||||
define HAL_BATT_CURR_PIN 11
|
||||
define HAL_BATT_VOLT_SCALE 11
|
||||
define HAL_BATT_CURR_SCALE 18.2
|
||||
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
|
||||
define BOARD_PWM_COUNT_DEFAULT 4
|
||||
|
||||
#font for the osd
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
# disable parachute and sprayer to save flash
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
define HAL_SPRAYER_ENABLED 0
|
||||
|
||||
# reduce max size of embedded params for apj_tool.py
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
|
@ -7,14 +7,6 @@ MCU STM32F7xx STM32F767xx
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
define STM32_LSECLK 32768U
|
||||
define STM32_LSEDRV (3U << 3U)
|
||||
define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
define STM32_PLLM_VALUE 8
|
||||
define STM32_PLLN_VALUE 216
|
||||
define STM32_PLLP_VALUE 2
|
||||
define STM32_PLLQ_VALUE 9
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 50
|
||||
|
||||
@ -39,11 +31,9 @@ PC6 LED_BOOTLOADER OUTPUT HIGH
|
||||
PC7 LED_ACTIVITY OUTPUT HIGH
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART2 UART7
|
||||
SERIAL_ORDER OTG1 USART2 UART7
|
||||
|
||||
# USART2 is telem1
|
||||
PD6 USART2_RX USART2
|
||||
|
@ -13,7 +13,7 @@ undef PE3
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
|
||||
|
||||
# order of UARTs (and USB). Telem2 is UART4 on the mini, USART3 is not available
|
||||
UART_ORDER OTG1 USART1 USART2 UART4 USART6 UART7 OTG2
|
||||
SERIAL_ORDER OTG1 USART2 UART4 USART1 USART6 UART7 OTG2
|
||||
|
||||
# enable TX on USART6 (disabled for fmuv5 with iomcu)
|
||||
PG14 USART6_TX USART6 NODMA
|
||||
|
@ -10,13 +10,10 @@ APJ_BOARD_ID 1151
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# USB setup
|
||||
USB_VENDOR 0x27AC
|
||||
@ -38,7 +35,7 @@ STM32_ST_USE_TIMER 5
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA9 VBUS INPUT
|
||||
|
||||
|
@ -11,13 +11,10 @@ APJ_BOARD_ID 1151
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# USB setup
|
||||
USB_VENDOR 0x27AC
|
||||
@ -32,7 +29,7 @@ STM32_ST_USE_TIMER 5
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART3 USART2
|
||||
SERIAL_ORDER OTG1 USART3 USART2 USART1
|
||||
STDOUT_SERIAL SD3
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
@ -136,7 +133,6 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
define STORAGE_FLASH_PAGE 22
|
||||
|
||||
# enable RAMTROM parameter storage
|
||||
define HAL_WITH_RAMTRON 1
|
||||
|
@ -10,13 +10,10 @@ APJ_BOARD_ID 1152
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# USB setup
|
||||
USB_VENDOR 0x27AC
|
||||
@ -38,7 +35,7 @@ STM32_ST_USE_TIMER 5
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA9 VBUS INPUT
|
||||
|
||||
|
@ -11,13 +11,10 @@ APJ_BOARD_ID 1152
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# USB setup
|
||||
USB_VENDOR 0x27AC
|
||||
@ -32,7 +29,7 @@ STM32_ST_USE_TIMER 5
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART3 USART2
|
||||
SERIAL_ORDER OTG1 USART3 USART2 USART1
|
||||
STDOUT_SERIAL SD3
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
@ -136,7 +133,6 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
define STORAGE_FLASH_PAGE 22
|
||||
|
||||
# enable RAMTROM parameter storage
|
||||
define HAL_WITH_RAMTRON 1
|
||||
|
@ -15,8 +15,6 @@ OSCILLATOR_HZ 24000000
|
||||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# USB setup
|
||||
USB_VENDOR 0x27AC
|
||||
@ -38,7 +36,7 @@ STM32_ST_USE_TIMER 5
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA9 VBUS INPUT
|
||||
|
||||
|
@ -16,8 +16,6 @@ OSCILLATOR_HZ 24000000
|
||||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# USB setup
|
||||
USB_VENDOR 0x27AC
|
||||
@ -32,7 +30,7 @@ STM32_ST_USE_TIMER 5
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART3 USART2
|
||||
SERIAL_ORDER OTG1 USART3 USART2 USART1
|
||||
STDOUT_SERIAL SD3
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
@ -136,7 +134,6 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
define STORAGE_FLASH_PAGE 22
|
||||
|
||||
# enable RAMTROM parameter storage
|
||||
define HAL_WITH_RAMTRON 1
|
||||
|
@ -10,13 +10,10 @@ APJ_BOARD_ID 1910
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# USB setup
|
||||
USB_VENDOR 0x27AC
|
||||
@ -38,7 +35,7 @@ STM32_ST_USE_TIMER 5
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA9 VBUS INPUT
|
||||
|
||||
|
@ -11,13 +11,10 @@ APJ_BOARD_ID 1910
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# USB setup
|
||||
USB_VENDOR 0x27AC
|
||||
@ -32,7 +29,7 @@ STM32_ST_USE_TIMER 5
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART3 USART2
|
||||
SERIAL_ORDER OTG1 USART3 USART2 USART1
|
||||
STDOUT_SERIAL SD3
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
@ -136,7 +133,6 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
define STORAGE_FLASH_PAGE 22
|
||||
|
||||
# enable RAMTROM parameter storage
|
||||
define HAL_WITH_RAMTRON 1
|
||||
|
@ -10,13 +10,10 @@ APJ_BOARD_ID 1351
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# USB setup
|
||||
USB_VENDOR 0x27AC
|
||||
@ -38,7 +35,7 @@ STM32_ST_USE_TIMER 5
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA9 VBUS INPUT
|
||||
|
||||
|
@ -11,13 +11,10 @@ APJ_BOARD_ID 1351
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# USB setup
|
||||
USB_VENDOR 0x27AC
|
||||
@ -32,7 +29,7 @@ STM32_ST_USE_TIMER 5
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART3 USART2
|
||||
SERIAL_ORDER OTG1 USART3 USART2 USART1
|
||||
STDOUT_SERIAL SD3
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
@ -143,6 +140,8 @@ FLASH_RESERVE_START_KB 64
|
||||
# enable RAMTROM parameter storage
|
||||
#define HAL_WITH_RAMTRON 1
|
||||
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
|
||||
|
||||
# enable FAT filesystem
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
|
@ -9,7 +9,7 @@ FLASH_RESERVE_START_KB 0
|
||||
FLASH_BOOTLOADER_LOAD_KB 34
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1003
|
||||
APJ_BOARD_ID 1005
|
||||
|
||||
# setup build for a peripheral firmware
|
||||
env AP_PERIPH 1
|
||||
@ -17,7 +17,9 @@ env AP_PERIPH 1
|
||||
define HAL_BOARD_AP_PERIPH_ZUBAXGNSS
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_ZubaxGNSS"
|
||||
define HAL_CAN_DEFAULT_NODE_ID 114
|
||||
|
||||
# use DNA
|
||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
@ -40,8 +42,6 @@ RAM_RESERVE_START 256
|
||||
PB10 USART3_TX USART3 SPEED_HIGH NODMA
|
||||
PB11 USART3_RX USART3 SPEED_HIGH NODMA
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
PB7 PERIPH_RESET OUTPUT HIGH
|
||||
|
||||
@ -120,7 +120,7 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 0
|
||||
PA2 USART2_TX USART2 SPEED_HIGH NODMA
|
||||
PA3 USART2_RX USART2 SPEED_HIGH NODMA
|
||||
|
||||
UART_ORDER
|
||||
SERIAL_ORDER
|
||||
|
||||
define HAL_STORAGE_SIZE 800
|
||||
|
||||
|
@ -20,7 +20,7 @@ define STORAGE_FLASH_PAGE 126
|
||||
define HAL_STORAGE_SIZE 800
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1003
|
||||
APJ_BOARD_ID 1005
|
||||
|
||||
# setup build for a peripheral firmware
|
||||
env AP_PERIPH 1
|
||||
@ -42,8 +42,6 @@ FLASH_RESERVE_END_KB 2
|
||||
STDOUT_SERIAL SD3
|
||||
STDOUT_BAUDRATE 115200
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# enable pin for GPS
|
||||
PB7 GPS_ENABLE OUTPUT HIGH
|
||||
@ -93,7 +91,7 @@ PC12 SPI3_MOSI SPI3 SPEED_HIGH
|
||||
|
||||
#########################
|
||||
# order of UARTs
|
||||
UART_ORDER USART3 USART2
|
||||
SERIAL_ORDER USART3 EMPTY EMPTY USART2
|
||||
|
||||
SPIDEV ms5611 SPI3 DEVID1 BARO_CS MODE3 8*MHZ 8*MHZ
|
||||
SPIDEV lis3mdl SPI3 DEVID2 MAG_CS MODE3 500*KHZ 500*KHZ
|
||||
@ -131,8 +129,6 @@ define STM32_I2C_USE_I2C1 TRUE
|
||||
define HAL_UART_MIN_TX_SIZE 256
|
||||
define HAL_UART_MIN_RX_SIZE 128
|
||||
|
||||
define CH_DBG_ENABLE_STACK_CHECK TRUE
|
||||
|
||||
define HAL_UART_STACK_SIZE 256
|
||||
define STORAGE_THD_WA_SIZE 512
|
||||
|
||||
@ -156,7 +152,8 @@ BARO MS56XX SPI:ms5611
|
||||
|
||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||
|
||||
define HAL_CAN_DEFAULT_NODE_ID 114
|
||||
# use DNA
|
||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_LOGGING
|
||||
|
@ -9,7 +9,6 @@ APJ_BOARD_ID 128
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
@ -26,11 +25,9 @@ define HAL_LED_ON 0
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 64
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
@ -11,10 +11,6 @@ APJ_BOARD_ID 128
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
STM32_ST_USE_TIMER 5
|
||||
|
||||
@ -26,7 +22,7 @@ FLASH_RESERVE_START_KB 64
|
||||
I2C_ORDER I2C2
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1 USART6 USART1
|
||||
SERIAL_ORDER OTG1 USART1 EMPTY USART6
|
||||
|
||||
#adc
|
||||
PC1 BAT_CURR_SENS ADC1 SCALE(1)
|
||||
@ -81,8 +77,6 @@ SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ
|
||||
# enable logging to dataflash
|
||||
define HAL_LOGGING_DATAFLASH
|
||||
|
||||
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_AIRBOTF4
|
||||
|
||||
# one IMU
|
||||
IMU Invensense SPI:mpu6000_cs ROTATION_YAW_180
|
||||
|
||||
|
@ -47,7 +47,7 @@ const PALConfig pal_default_config =
|
||||
{VAL_GPIOE_ODR, VAL_GPIOE_CRL, VAL_GPIOE_CRH},
|
||||
};
|
||||
|
||||
#else //Other than STM32F1 series
|
||||
#else //Other than STM32F1/F3 series
|
||||
|
||||
/**
|
||||
* @brief Type of STM32 GPIO port setup.
|
||||
@ -173,6 +173,9 @@ static void stm32_gpio_init(void) {
|
||||
#if defined(STM32H7)
|
||||
rccResetAHB4(STM32_GPIO_EN_MASK);
|
||||
rccEnableAHB4(STM32_GPIO_EN_MASK, true);
|
||||
#elif defined(STM32F3)
|
||||
rccResetAHB(STM32_GPIO_EN_MASK);
|
||||
rccEnableAHB(STM32_GPIO_EN_MASK, true);
|
||||
#else
|
||||
rccResetAHB1(STM32_GPIO_EN_MASK);
|
||||
rccEnableAHB1(STM32_GPIO_EN_MASK, true);
|
||||
|
@ -266,7 +266,7 @@
|
||||
* @note Requires @p CH_CFG_USE_MUTEXES.
|
||||
*/
|
||||
#if !defined(CH_CFG_USE_MUTEXES_RECURSIVE)
|
||||
#define CH_CFG_USE_MUTEXES_RECURSIVE FALSE
|
||||
#define CH_CFG_USE_MUTEXES_RECURSIVE TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
@ -575,7 +575,7 @@
|
||||
* @p panic_msg variable set to @p NULL.
|
||||
*/
|
||||
#if !defined(CH_DBG_ENABLE_STACK_CHECK)
|
||||
#define CH_DBG_ENABLE_STACK_CHECK FALSE
|
||||
#define CH_DBG_ENABLE_STACK_CHECK TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
@ -725,9 +725,20 @@
|
||||
#define CH_CFG_SYSTEM_HALT_HOOK(reason) do { \
|
||||
extern void memory_flush_all(void); \
|
||||
memory_flush_all(); \
|
||||
extern void system_halt_hook(void); \
|
||||
system_halt_hook(); \
|
||||
} while(0)
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief stack overflow event hook.
|
||||
* @details This hook is invoked when we have a stack overflow on task switch
|
||||
*/
|
||||
#define CH_CFG_STACK_OVERFLOW_HOOK(tp) { \
|
||||
extern void stack_overflow(thread_t *tp); \
|
||||
stack_overflow(tp); \
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Trace hook.
|
||||
* @details This hook is invoked each time a new record is written in the
|
||||
|
@ -70,6 +70,9 @@ SECTIONS
|
||||
|
||||
.text : ALIGN(4) SUBALIGN(4)
|
||||
{
|
||||
/* we want app_descriptor near the start of flash so a false
|
||||
positive isn't found by the bootloader (eg. ROMFS) */
|
||||
KEEP(*(.app_descriptor));
|
||||
*(.text)
|
||||
*(.text.*)
|
||||
*(.rodata)
|
||||
|
@ -53,6 +53,8 @@
|
||||
#include <string.h>
|
||||
#include "stm32_util.h"
|
||||
|
||||
#include <assert.h>
|
||||
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
/*
|
||||
@ -118,10 +120,18 @@ static const uint32_t flash_memmap[STM32_FLASH_NPAGES] = { KB(32), KB(32), KB(32
|
||||
#elif defined(STM32F105_MCUCONF)
|
||||
#define STM32_FLASH_NPAGES (BOARD_FLASH_SIZE/2)
|
||||
#define STM32_FLASH_FIXED_PAGE_SIZE 2
|
||||
#elif defined(STM32F303_MCUCONF)
|
||||
#define STM32_FLASH_NPAGES (BOARD_FLASH_SIZE/2)
|
||||
#define STM32_FLASH_FIXED_PAGE_SIZE 2
|
||||
#else
|
||||
#error "Unsupported processor for flash.c"
|
||||
#endif
|
||||
|
||||
#ifdef STORAGE_FLASH_PAGE
|
||||
static_assert(STORAGE_FLASH_PAGE < STM32_FLASH_NPAGES,
|
||||
"STORAGE_FLASH_PAGE out of range");
|
||||
#endif
|
||||
|
||||
// keep a cache of the page addresses
|
||||
#ifndef STM32_FLASH_FIXED_PAGE_SIZE
|
||||
static uint32_t flash_pageaddr[STM32_FLASH_NPAGES];
|
||||
@ -366,7 +376,7 @@ bool stm32_flash_erasepage(uint32_t page)
|
||||
FLASH->CR2 |= FLASH_CR_START;
|
||||
while (FLASH->SR2 & FLASH_SR_QW) ;
|
||||
}
|
||||
#elif defined(STM32F1)
|
||||
#elif defined(STM32F1) || defined(STM32F3)
|
||||
FLASH->CR = FLASH_CR_PER;
|
||||
FLASH->AR = stm32_flash_getpageaddr(page);
|
||||
FLASH->CR |= FLASH_CR_STRT;
|
||||
@ -438,7 +448,8 @@ static bool stm32_flash_write_h7(uint32_t addr, const void *buf, uint32_t count)
|
||||
}
|
||||
stm32_flash_unlock();
|
||||
while (count >= 32) {
|
||||
if (!stm32h7_flash_write32(addr, b)) {
|
||||
if (memcmp((void*)addr, b, 32) != 0 &&
|
||||
!stm32h7_flash_write32(addr, b)) {
|
||||
return false;
|
||||
}
|
||||
// check contents
|
||||
@ -556,7 +567,7 @@ uint32_t _flash_fail_addr;
|
||||
uint32_t _flash_fail_count;
|
||||
uint8_t *_flash_fail_buf;
|
||||
|
||||
#if defined(STM32F1)
|
||||
#if defined(STM32F1) || defined(STM32F3)
|
||||
static bool stm32_flash_write_f1(uint32_t addr, const void *buf, uint32_t count)
|
||||
{
|
||||
uint8_t *b = (uint8_t *)buf;
|
||||
@ -616,11 +627,11 @@ failed:
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
#endif // STM32F1
|
||||
#endif // STM32F1 or STM32F3
|
||||
|
||||
bool stm32_flash_write(uint32_t addr, const void *buf, uint32_t count)
|
||||
{
|
||||
#if defined(STM32F1)
|
||||
#if defined(STM32F1) || defined(STM32F3)
|
||||
return stm32_flash_write_f1(addr, buf, count);
|
||||
#elif defined(STM32F4) || defined(STM32F7)
|
||||
return stm32_flash_write_f4f7(addr, buf, count);
|
||||
|
@ -263,7 +263,7 @@
|
||||
* @brief Enforces the driver to use direct callbacks rather than OSAL events.
|
||||
*/
|
||||
#if !defined(CAN_ENFORCE_USE_CALLBACKS) || defined(__DOXYGEN__)
|
||||
#define CAN_ENFORCE_USE_CALLBACKS FALSE
|
||||
#define CAN_ENFORCE_USE_CALLBACKS TRUE
|
||||
#endif
|
||||
|
||||
/*===========================================================================*/
|
||||
|
@ -41,16 +41,12 @@
|
||||
for micros64()
|
||||
*/
|
||||
|
||||
#if CH_CFG_ST_FREQUENCY != 1000000U && CH_CFG_ST_FREQUENCY != 1000U
|
||||
#error "unsupported tick frequency"
|
||||
#endif
|
||||
|
||||
#if CH_CFG_ST_RESOLUTION == 16
|
||||
static uint32_t system_time_u32_us(void)
|
||||
{
|
||||
systime_t now = chVTGetSystemTimeX();
|
||||
#if CH_CFG_ST_FREQUENCY == 1000U
|
||||
now *= 1000U;
|
||||
#if CH_CFG_ST_FREQUENCY != 1000000U
|
||||
#error "must use 32 bit timer if system clock not 1MHz"
|
||||
#endif
|
||||
static systime_t last_systime;
|
||||
static uint32_t timer_base_us32;
|
||||
@ -63,8 +59,8 @@ static uint32_t system_time_u32_us(void)
|
||||
static uint32_t system_time_u32_us(void)
|
||||
{
|
||||
systime_t now = chVTGetSystemTimeX();
|
||||
#if CH_CFG_ST_FREQUENCY == 1000U
|
||||
now *= 1000U;
|
||||
#if CH_CFG_ST_FREQUENCY != 1000000U
|
||||
now *= 1000000U/CH_CFG_ST_FREQUENCY;
|
||||
#endif
|
||||
return now;
|
||||
}
|
||||
|
@ -287,3 +287,18 @@ void memory_flush_all(void)
|
||||
stm32_cacheBufferFlush(memory_regions[i].address, memory_regions[i].size);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
replacement for strdup
|
||||
*/
|
||||
char *strdup(const char *str)
|
||||
{
|
||||
const size_t len = strlen(str);
|
||||
char *ret = malloc(len+1);
|
||||
if (!ret) {
|
||||
return NULL;
|
||||
}
|
||||
memcpy(ret, str, len);
|
||||
ret[len] = 0;
|
||||
return ret;
|
||||
}
|
||||
|
@ -39,6 +39,8 @@
|
||||
|
||||
#if defined(STM32F1)
|
||||
#include "stm32f1_mcuconf.h"
|
||||
#elif defined(STM32F3)
|
||||
#include "stm32f3_mcuconf.h"
|
||||
#elif defined(STM32F4) || defined(STM32F7)
|
||||
#include "stm32f47_mcuconf.h"
|
||||
#elif defined(STM32H7)
|
||||
|
@ -260,8 +260,10 @@ enum rtc_boot_magic check_fast_reboot(void)
|
||||
// set RTC register for a fast reboot
|
||||
void set_fast_reboot(enum rtc_boot_magic v)
|
||||
{
|
||||
uint32_t vv = (uint32_t)v;
|
||||
set_rtc_backup(0, &vv, 1);
|
||||
if (check_fast_reboot() != v) {
|
||||
uint32_t vv = (uint32_t)v;
|
||||
set_rtc_backup(0, &vv, 1);
|
||||
}
|
||||
}
|
||||
|
||||
#else // NO_FASTBOOT
|
||||
@ -319,7 +321,7 @@ void peripheral_power_enable(void)
|
||||
#endif
|
||||
}
|
||||
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32F3)
|
||||
/*
|
||||
read mode of a pin. This allows a pin config to be read, changed and
|
||||
then written back
|
||||
@ -340,7 +342,18 @@ iomode_t palReadLineMode(ioline_t line)
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
set pin as pullup, pulldown or floating
|
||||
*/
|
||||
void palLineSetPushPull(ioline_t line, enum PalPushPull pp)
|
||||
{
|
||||
ioportid_t port = PAL_PORT(line);
|
||||
uint8_t pad = PAL_PAD(line);
|
||||
port->PUPDR = (port->PUPDR & ~(3<<(pad*2))) | (pp<<(pad*2));
|
||||
}
|
||||
|
||||
#endif // F7, H7, F4
|
||||
|
||||
void stm32_cacheBufferInvalidate(const void *p, size_t size)
|
||||
{
|
||||
@ -351,3 +364,88 @@ void stm32_cacheBufferFlush(const void *p, size_t size)
|
||||
{
|
||||
cacheBufferFlush(p, size);
|
||||
}
|
||||
|
||||
|
||||
#ifdef HAL_GPIO_PIN_FAULT
|
||||
/*
|
||||
optional support for hard-fault debugging using soft-serial output to a pin
|
||||
To use this setup a pin like this:
|
||||
|
||||
Pxx FAULT OUTPUT HIGH
|
||||
|
||||
for some pin Pxx
|
||||
|
||||
On a STM32F405 the baudrate will be around 42kBaud. Use the
|
||||
auto-baud function on your logic analyser to decode
|
||||
*/
|
||||
/*
|
||||
send one bit out a debug line
|
||||
*/
|
||||
static void fault_send_bit(ioline_t line, uint8_t b)
|
||||
{
|
||||
palWriteLine(line, b);
|
||||
for (uint32_t i=0; i<1000; i++) {
|
||||
palWriteLine(line, b);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
send a byte out a debug line
|
||||
*/
|
||||
static void fault_send_byte(ioline_t line, uint8_t b)
|
||||
{
|
||||
fault_send_bit(line, 0); // start bit
|
||||
for (uint8_t i=0; i<8; i++) {
|
||||
uint8_t bit = (b & (1U<<i))?1:0;
|
||||
fault_send_bit(line, bit);
|
||||
}
|
||||
fault_send_bit(line, 1); // stop bit
|
||||
}
|
||||
|
||||
/*
|
||||
send a string out a debug line
|
||||
*/
|
||||
static void fault_send_string(const char *str)
|
||||
{
|
||||
while (*str) {
|
||||
fault_send_byte(HAL_GPIO_PIN_FAULT, (uint8_t)*str++);
|
||||
}
|
||||
fault_send_byte(HAL_GPIO_PIN_FAULT, (uint8_t)'\n');
|
||||
}
|
||||
|
||||
void fault_printf(const char *fmt, ...)
|
||||
{
|
||||
static char buffer[100];
|
||||
va_list ap;
|
||||
va_start(ap, fmt);
|
||||
vsnprintf(buffer, sizeof(buffer), fmt, ap);
|
||||
va_end(ap);
|
||||
fault_send_string(buffer);
|
||||
}
|
||||
#endif // HAL_GPIO_PIN_HARDFAULT
|
||||
|
||||
void system_halt_hook(void)
|
||||
{
|
||||
#ifdef HAL_GPIO_PIN_FAULT
|
||||
// optionally print the message on a fault pin
|
||||
while (true) {
|
||||
fault_printf("PANIC:%s\n", ch.dbg.panic_msg);
|
||||
fault_printf("RA0:0x%08x\n", __builtin_return_address(0));
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// hook for stack overflow
|
||||
void stack_overflow(thread_t *tp)
|
||||
{
|
||||
#if !defined(HAL_BOOTLOADER_BUILD) && !defined(IOMCU_FW)
|
||||
extern void AP_stack_overflow(const char *thread_name);
|
||||
AP_stack_overflow(tp->name);
|
||||
// if we get here then we are armed and got a stack overflow. We
|
||||
// will report an internal error and keep trying to fly. We are
|
||||
// quite likely to crash anyway due to memory corruption. The
|
||||
// watchdog data should record the thread name and fault type
|
||||
#else
|
||||
(void)tp;
|
||||
#endif
|
||||
}
|
||||
|
@ -58,7 +58,8 @@ enum rtc_boot_magic {
|
||||
RTC_BOOT_OFF = 0,
|
||||
RTC_BOOT_HOLD = 0xb0070001,
|
||||
RTC_BOOT_FAST = 0xb0070002,
|
||||
RTC_BOOT_CANBL = 0xb0080000 // ORd with 8 bit local node ID
|
||||
RTC_BOOT_CANBL = 0xb0080000, // ORd with 8 bit local node ID
|
||||
RTC_BOOT_FWOK = 0xb0093a26 // indicates FW ran for 30s
|
||||
};
|
||||
|
||||
// see if RTC registers is setup for a fast reboot
|
||||
@ -77,8 +78,16 @@ void malloc_init(void);
|
||||
read mode of a pin. This allows a pin config to be read, changed and
|
||||
then written back
|
||||
*/
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4)
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32F3)
|
||||
iomode_t palReadLineMode(ioline_t line);
|
||||
|
||||
enum PalPushPull {
|
||||
PAL_PUSHPULL_NOPULL=0,
|
||||
PAL_PUSHPULL_PULLUP=1,
|
||||
PAL_PUSHPULL_PULLDOWN=2
|
||||
};
|
||||
|
||||
void palLineSetPushPull(ioline_t line, enum PalPushPull pp);
|
||||
#endif
|
||||
|
||||
// set n RTC backup registers starting at given idx
|
||||
@ -90,6 +99,17 @@ void get_rtc_backup(uint8_t idx, uint32_t *v, uint8_t n);
|
||||
void stm32_cacheBufferInvalidate(const void *p, size_t size);
|
||||
void stm32_cacheBufferFlush(const void *p, size_t size);
|
||||
|
||||
#ifdef HAL_GPIO_PIN_FAULT
|
||||
// printf for fault handlers
|
||||
void fault_printf(const char *fmt, ...);
|
||||
#endif
|
||||
|
||||
// halt hook for printing panic message
|
||||
void system_halt_hook(void);
|
||||
|
||||
// hook for stack overflow
|
||||
void stack_overflow(thread_t *tp);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
174
libraries/AP_HAL_ChibiOS/hwdef/common/stm32f3_mcuconf.h
Normal file
174
libraries/AP_HAL_ChibiOS/hwdef/common/stm32f3_mcuconf.h
Normal file
@ -0,0 +1,174 @@
|
||||
/*
|
||||
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
|
||||
Licensed under the Apache License, Version 2.0 (the "License");
|
||||
you may not use this file except in compliance with the License.
|
||||
You may obtain a copy of the License at
|
||||
http://www.apache.org/licenses/LICENSE-2.0
|
||||
Unless required by applicable law or agreed to in writing, software
|
||||
distributed under the License is distributed on an "AS IS" BASIS,
|
||||
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
See the License for the specific language governing permissions and
|
||||
limitations under the License.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
/*
|
||||
* STM32F303 drivers configuration.
|
||||
* The following settings override the default settings present in
|
||||
* the various device driver implementation headers.
|
||||
* Note that the settings for each driver only have effect if the whole
|
||||
* driver is enabled in halconf.h.
|
||||
*
|
||||
* IRQ priorities:
|
||||
* 15...0 Lowest...Highest.
|
||||
*
|
||||
* DMA priorities:
|
||||
* 0...3 Lowest...Highest.
|
||||
*/
|
||||
|
||||
#define STM32F3xx_MCUCONF
|
||||
|
||||
/*
|
||||
* HAL driver system settings.
|
||||
*/
|
||||
#define STM32_NO_INIT FALSE
|
||||
#define STM32_HSI_ENABLED FALSE
|
||||
#define STM32_LSI_ENABLED FALSE
|
||||
#define STM32_HSE_ENABLED TRUE
|
||||
#define STM32_LSE_ENABLED FALSE
|
||||
|
||||
#if STM32_HSECLK == 8000000U
|
||||
#define STM32_SW STM32_SW_PLL
|
||||
#define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
#define STM32_PLLXTPRE STM32_PLLXTPRE_DIV1
|
||||
#define STM32_PLLMUL_VALUE 9
|
||||
#define STM32_PPRE1 STM32_PPRE1_DIV2
|
||||
#define STM32_PPRE2 STM32_PPRE2_DIV2
|
||||
#define STM32_ADCPRE STM32_ADCPRE_DIV4
|
||||
#define STM32_HPRE STM32_HPRE_DIV1
|
||||
#elif STM32_HSECLK == 24000000U
|
||||
#define STM32_SW STM32_SW_PLL
|
||||
#define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
#define STM32_PLLXTPRE STM32_PLLXTPRE_DIV1
|
||||
#define STM32_PLLMUL_VALUE 3
|
||||
#define STM32_PPRE1 STM32_PPRE1_DIV2
|
||||
#define STM32_PPRE2 STM32_PPRE2_DIV2
|
||||
#define STM32_ADCPRE STM32_ADCPRE_DIV4
|
||||
#define STM32_HPRE STM32_HPRE_DIV1
|
||||
#else
|
||||
#error "Unsupported STM32F1xx clock frequency"
|
||||
#endif
|
||||
|
||||
#define STM32_MCOSEL STM32_MCOSEL_NOCLOCK
|
||||
#define STM32_RTCSEL STM32_RTCSEL_HSEDIV
|
||||
#define STM32_PVD_ENABLE FALSE
|
||||
#define STM32_PLS STM32_PLS_LEV0
|
||||
|
||||
/*
|
||||
* ADC driver system settings.
|
||||
*/
|
||||
#define STM32_ADC_ADC1_DMA_PRIORITY 2
|
||||
#define STM32_ADC_ADC1_IRQ_PRIORITY 6
|
||||
|
||||
/*
|
||||
* EXT driver system settings.
|
||||
*/
|
||||
#define STM32_EXT_EXTI0_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI1_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI2_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI3_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI4_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI5_9_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI10_15_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI16_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI17_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI18_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI19_IRQ_PRIORITY 6
|
||||
|
||||
/*
|
||||
* GPT driver system settings.
|
||||
*/
|
||||
#define STM32_GPT_TIM1_IRQ_PRIORITY 7
|
||||
#define STM32_GPT_TIM2_IRQ_PRIORITY 7
|
||||
#define STM32_GPT_TIM3_IRQ_PRIORITY 7
|
||||
#define STM32_GPT_TIM4_IRQ_PRIORITY 7
|
||||
#define STM32_GPT_TIM5_IRQ_PRIORITY 7
|
||||
#define STM32_GPT_TIM8_IRQ_PRIORITY 7
|
||||
|
||||
/*
|
||||
* I2C driver system settings.
|
||||
*/
|
||||
#define STM32_I2C_BUSY_TIMEOUT 50
|
||||
#define STM32_I2C_I2C1_IRQ_PRIORITY 5
|
||||
#define STM32_I2C_I2C2_IRQ_PRIORITY 5
|
||||
#define STM32_I2C_I2C1_DMA_PRIORITY 3
|
||||
#define STM32_I2C_I2C2_DMA_PRIORITY 3
|
||||
#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure")
|
||||
|
||||
/*
|
||||
* ICU driver system settings.
|
||||
*/
|
||||
#define STM32_ICU_TIM1_IRQ_PRIORITY 7
|
||||
#define STM32_ICU_TIM2_IRQ_PRIORITY 7
|
||||
#define STM32_ICU_TIM3_IRQ_PRIORITY 7
|
||||
#define STM32_ICU_TIM4_IRQ_PRIORITY 7
|
||||
#define STM32_ICU_TIM5_IRQ_PRIORITY 7
|
||||
#define STM32_ICU_TIM8_IRQ_PRIORITY 7
|
||||
|
||||
/*
|
||||
* PWM driver system settings.
|
||||
*/
|
||||
#define STM32_PWM_TIM1_IRQ_PRIORITY 7
|
||||
#define STM32_PWM_TIM2_IRQ_PRIORITY 7
|
||||
#define STM32_PWM_TIM3_IRQ_PRIORITY 7
|
||||
#define STM32_PWM_TIM4_IRQ_PRIORITY 7
|
||||
#define STM32_PWM_TIM5_IRQ_PRIORITY 7
|
||||
#define STM32_PWM_TIM8_IRQ_PRIORITY 7
|
||||
|
||||
/*
|
||||
* RTC driver system settings.
|
||||
*/
|
||||
#define STM32_RTC_IRQ_PRIORITY 15
|
||||
|
||||
/*
|
||||
* SERIAL driver system settings.
|
||||
*/
|
||||
#define STM32_SERIAL_USART1_PRIORITY 12
|
||||
#define STM32_SERIAL_USART2_PRIORITY 12
|
||||
#define STM32_SERIAL_USART3_PRIORITY 12
|
||||
|
||||
/*
|
||||
* SPI driver system settings.
|
||||
*/
|
||||
#define STM32_SPI_SPI1_DMA_PRIORITY 1
|
||||
#define STM32_SPI_SPI2_DMA_PRIORITY 1
|
||||
#define STM32_SPI_SPI1_IRQ_PRIORITY 10
|
||||
#define STM32_SPI_SPI2_IRQ_PRIORITY 10
|
||||
#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure")
|
||||
|
||||
/*
|
||||
* ST driver system settings.
|
||||
*/
|
||||
#define STM32_ST_IRQ_PRIORITY 8
|
||||
#ifndef STM32_ST_USE_TIMER
|
||||
#define STM32_ST_USE_TIMER 2
|
||||
#endif
|
||||
/*
|
||||
* UART driver system settings.
|
||||
*/
|
||||
#define STM32_UART_USART1_IRQ_PRIORITY 12
|
||||
#define STM32_UART_USART2_IRQ_PRIORITY 12
|
||||
#define STM32_UART_USART3_IRQ_PRIORITY 12
|
||||
#define STM32_UART_USART1_DMA_PRIORITY 0
|
||||
#define STM32_UART_USART2_DMA_PRIORITY 0
|
||||
#define STM32_UART_USART3_DMA_PRIORITY 0
|
||||
#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure")
|
||||
|
||||
/*
|
||||
* WDG driver system settings.
|
||||
*/
|
||||
#define STM32_WDG_USE_IWDG FALSE
|
||||
|
||||
#ifndef STM32_ADC_USE_ADC1
|
||||
#define STM32_ADC_USE_ADC1 FALSE
|
||||
#endif
|
@ -81,28 +81,60 @@
|
||||
#ifndef STM32_PLLSRC
|
||||
#define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
#endif
|
||||
#ifndef STM32_PLLM_VALUE
|
||||
#define STM32_PLLM_VALUE 24
|
||||
#endif
|
||||
#ifndef STM32_PLLN_VALUE
|
||||
#define STM32_PLLN_VALUE 336
|
||||
#endif
|
||||
#ifndef STM32_PLLP_VALUE
|
||||
#define STM32_PLLP_VALUE 2
|
||||
#endif
|
||||
#ifndef STM32_PLLQ_VALUE
|
||||
#define STM32_PLLQ_VALUE 7
|
||||
#endif
|
||||
|
||||
#ifndef STM32_HPRE
|
||||
#if !defined(HAL_CUSTOM_CLOCK_TREE)
|
||||
#if defined(STM32F7xx_MCUCONF)
|
||||
// F7 clock config
|
||||
#if STM32_HSECLK == 8000000U
|
||||
#define STM32_PLLM_VALUE 8
|
||||
#define STM32_PLLN_VALUE 432
|
||||
#define STM32_PLLP_VALUE 2
|
||||
#define STM32_PLLQ_VALUE 9
|
||||
#elif STM32_HSECLK == 16000000U
|
||||
#define STM32_PLLM_VALUE 8
|
||||
#define STM32_PLLN_VALUE 216
|
||||
#define STM32_PLLP_VALUE 2
|
||||
#define STM32_PLLQ_VALUE 9
|
||||
#elif STM32_HSECLK == 24000000U
|
||||
#define STM32_PLLM_VALUE 24
|
||||
#define STM32_PLLN_VALUE 432
|
||||
#define STM32_PLLP_VALUE 2
|
||||
#define STM32_PLLQ_VALUE 9
|
||||
#else
|
||||
#error "Unsupported F7 HSE clock"
|
||||
#endif
|
||||
#else // F4
|
||||
// F4 clock config
|
||||
#if STM32_HSECLK == 8000000U
|
||||
#define STM32_PLLM_VALUE 8
|
||||
#define STM32_PLLN_VALUE 336
|
||||
#define STM32_PLLP_VALUE 2
|
||||
#define STM32_PLLQ_VALUE 7
|
||||
#elif STM32_HSECLK == 16000000U
|
||||
#define STM32_PLLM_VALUE 16
|
||||
#define STM32_PLLN_VALUE 384
|
||||
#define STM32_PLLP_VALUE 4
|
||||
#define STM32_PLLQ_VALUE 8
|
||||
#elif STM32_HSECLK == 24000000U
|
||||
#define STM32_PLLM_VALUE 24
|
||||
#define STM32_PLLN_VALUE 336
|
||||
#define STM32_PLLP_VALUE 2
|
||||
#define STM32_PLLQ_VALUE 7
|
||||
#else
|
||||
#error "Unsupported F4 HSE clock"
|
||||
#endif
|
||||
#endif // MCU
|
||||
#endif // HAL_CUSTOM_CLOCK_TREE
|
||||
|
||||
// we don't use LSE, but we need the defines
|
||||
#define STM32_LSECLK 32768U
|
||||
#define STM32_LSEDRV (3U << 3U)
|
||||
|
||||
#define STM32_VDD 330U
|
||||
|
||||
#define STM32_HPRE STM32_HPRE_DIV1
|
||||
#endif
|
||||
#ifndef STM32_PPRE1
|
||||
#define STM32_PPRE1 STM32_PPRE1_DIV4
|
||||
#endif
|
||||
#ifndef STM32_PPRE2
|
||||
#define STM32_PPRE2 STM32_PPRE2_DIV2
|
||||
#endif
|
||||
#define STM32_RTCSEL STM32_RTCSEL_LSI
|
||||
#define STM32_RTCPRE_VALUE 8
|
||||
#define STM32_MCO1SEL STM32_MCO1SEL_HSI
|
||||
|
@ -87,6 +87,11 @@
|
||||
#define STM32_PLL1_DIVM_VALUE 3
|
||||
#define STM32_PLL2_DIVM_VALUE 3
|
||||
#define STM32_PLL3_DIVM_VALUE 6
|
||||
#elif STM32_HSECLK == 25000000U
|
||||
// this gives 400MHz system clock
|
||||
#define STM32_PLL1_DIVM_VALUE 2
|
||||
#define STM32_PLL2_DIVM_VALUE 2
|
||||
#define STM32_PLL3_DIVM_VALUE 5
|
||||
#else
|
||||
#error "Unsupported HSE clock"
|
||||
#endif
|
||||
@ -100,14 +105,30 @@
|
||||
|
||||
#define STM32_PLL2_DIVN_VALUE 25
|
||||
#define STM32_PLL2_DIVP_VALUE 2
|
||||
#define STM32_PLL2_DIVQ_VALUE 2
|
||||
#define STM32_PLL2_DIVQ_VALUE 4
|
||||
#define STM32_PLL2_DIVR_VALUE 2
|
||||
|
||||
#define STM32_PLL3_DIVN_VALUE 72
|
||||
#define STM32_PLL3_DIVP_VALUE 3
|
||||
#define STM32_PLL3_DIVQ_VALUE 6
|
||||
#define STM32_PLL3_DIVR_VALUE 9
|
||||
#endif // 8MHz clock multiples
|
||||
|
||||
#elif STM32_HSECLK == 25000000U
|
||||
#define STM32_PLL1_DIVN_VALUE 64
|
||||
#define STM32_PLL1_DIVP_VALUE 2
|
||||
#define STM32_PLL1_DIVQ_VALUE 8
|
||||
#define STM32_PLL1_DIVR_VALUE 2
|
||||
|
||||
#define STM32_PLL2_DIVN_VALUE 12
|
||||
#define STM32_PLL2_DIVP_VALUE 1
|
||||
#define STM32_PLL2_DIVQ_VALUE 2
|
||||
#define STM32_PLL2_DIVR_VALUE 2
|
||||
|
||||
#define STM32_PLL3_DIVN_VALUE 48
|
||||
#define STM32_PLL3_DIVP_VALUE 3
|
||||
#define STM32_PLL3_DIVQ_VALUE 5
|
||||
#define STM32_PLL3_DIVR_VALUE 8
|
||||
#endif // clock selection
|
||||
|
||||
#define STM32_PLL1_ENABLED TRUE
|
||||
#define STM32_PLL1_P_ENABLED TRUE
|
||||
@ -158,10 +179,10 @@
|
||||
#define STM32_QSPISEL STM32_QSPISEL_HCLK
|
||||
#define STM32_FMCSEL STM32_QSPISEL_HCLK
|
||||
#define STM32_SWPSEL STM32_SWPSEL_PCLK1
|
||||
#define STM32_FDCANSEL STM32_FDCANSEL_PLL1_Q_CK
|
||||
#define STM32_FDCANSEL STM32_FDCANSEL_PLL2_Q_CK
|
||||
#define STM32_DFSDM1SEL STM32_DFSDM1SEL_PCLK2
|
||||
#define STM32_SPDIFSEL STM32_SPDIFSEL_PLL1_Q_CK
|
||||
#define STM32_SPI45SEL STM32_SPI45SEL_PLL2_Q_CK
|
||||
#define STM32_SPI45SEL STM32_SPI45SEL_PCLK2
|
||||
#define STM32_SPI123SEL STM32_SPI123SEL_PLL1_Q_CK
|
||||
#define STM32_SAI23SEL STM32_SAI23SEL_PLL1_Q_CK
|
||||
#define STM32_SAI1SEL STM32_SAI1SEL_PLL1_Q_CK
|
||||
@ -172,7 +193,7 @@
|
||||
#define STM32_RNGSEL STM32_RNGSEL_HSI48_CK
|
||||
#define STM32_USART16SEL STM32_USART16SEL_PCLK2
|
||||
#define STM32_USART234578SEL STM32_USART234578SEL_PCLK1
|
||||
#define STM32_SPI6SEL STM32_SPI6SEL_PLL2_Q_CK
|
||||
#define STM32_SPI6SEL STM32_SPI6SEL_PCLK4
|
||||
#define STM32_SAI4BSEL STM32_SAI4BSEL_PLL1_Q_CK
|
||||
#define STM32_SAI4ASEL STM32_SAI4ASEL_PLL1_Q_CK
|
||||
#define STM32_ADCSEL STM32_ADCSEL_PLL3_R_CK
|
||||
|
@ -11,7 +11,7 @@
|
||||
#define IWDG_BASE 0x58004800
|
||||
#elif defined(STM32F7) || defined(STM32F4)
|
||||
#define IWDG_BASE 0x40003000
|
||||
#elif defined(STM32F1)
|
||||
#elif defined(STM32F1) || defined(STM32F3)
|
||||
#define IWDG_BASE 0x40003000
|
||||
#else
|
||||
#error "Unsupported IWDG MCU config"
|
||||
@ -33,7 +33,7 @@
|
||||
#define WDG_RESET_STATUS (*(__IO uint32_t *)(RCC_BASE + 0x74))
|
||||
#define WDG_RESET_CLEAR (1U<<24)
|
||||
#define WDG_RESET_IS_IWDG (1U<<29)
|
||||
#elif defined(STM32F1)
|
||||
#elif defined(STM32F1) || defined(STM32F3)
|
||||
#define WDG_RESET_STATUS (*(__IO uint32_t *)(RCC_BASE + 0x24))
|
||||
#define WDG_RESET_CLEAR (1U<<24)
|
||||
#define WDG_RESET_IS_IWDG (1U<<29)
|
||||
|
@ -1,3 +1,4 @@
|
||||
#pragma once
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user