forked from Archive/PX4-Autopilot
uavcan drivers: remove unused code for other OSs/bare metal
This commit is contained in:
parent
5dff065ec5
commit
6049a95073
|
@ -18,11 +18,10 @@ and the following commandline defines:
|
|||
|UAVCAN_KINETIS_TIMER_NUMBER | - {0..3} Sets the Periodic Interrupt Timer (PITn) channel |
|
||||
|
||||
Things that could be improved:
|
||||
1. Support for Bare metal and other OS' (ChibiOS, FREERTOS)
|
||||
2. Build time command line configuartion of Mailbox/FIFO and filters
|
||||
3. Build time command line configuartion clock source
|
||||
1. Build time command line configuartion of Mailbox/FIFO and filters
|
||||
2. Build time command line configuartion clock source
|
||||
- Curently the driver use `const uavcan::uint8_t CLOCKSEL = 0;` To Select OSCERCLK
|
||||
4. Dynamic filter disable. There are no filter enable bits on the FlexCAN, just the number of Filters
|
||||
3. Dynamic filter disable. There are no filter enable bits on the FlexCAN, just the number of Filters
|
||||
can be set. But this changes the memory map. So the configuration show below has been chosen.
|
||||
|
||||
```
|
||||
|
|
|
@ -8,20 +8,8 @@
|
|||
/**
|
||||
* OS detection
|
||||
*/
|
||||
#ifndef UAVCAN_KINETIS_CHIBIOS
|
||||
# define UAVCAN_KINETIS_CHIBIOS 0
|
||||
#endif
|
||||
|
||||
#ifndef UAVCAN_KINETIS_NUTTX
|
||||
# define UAVCAN_KINETIS_NUTTX 0
|
||||
#endif
|
||||
|
||||
#ifndef UAVCAN_KINETIS_BAREMETAL
|
||||
# define UAVCAN_KINETIS_BAREMETAL 0
|
||||
#endif
|
||||
|
||||
#ifndef UAVCAN_KINETIS_FREERTOS
|
||||
# define UAVCAN_KINETIS_FREERTOS 0
|
||||
# error "Only NuttX is supported"
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
|
|
@ -7,20 +7,8 @@
|
|||
/**
|
||||
* OS detection
|
||||
*/
|
||||
#ifndef UAVCAN_STM32_CHIBIOS
|
||||
# define UAVCAN_STM32_CHIBIOS 0
|
||||
#endif
|
||||
|
||||
#ifndef UAVCAN_STM32_NUTTX
|
||||
# define UAVCAN_STM32_NUTTX 0
|
||||
#endif
|
||||
|
||||
#ifndef UAVCAN_STM32_BAREMETAL
|
||||
# define UAVCAN_STM32_BAREMETAL 0
|
||||
#endif
|
||||
|
||||
#ifndef UAVCAN_STM32_FREERTOS
|
||||
# define UAVCAN_STM32_FREERTOS 0
|
||||
# error "Only NuttX is supported"
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
|
|
@ -6,9 +6,7 @@
|
|||
|
||||
#include <uavcan_stm32/build_config.hpp>
|
||||
|
||||
#if UAVCAN_STM32_CHIBIOS
|
||||
# include <ch.hpp>
|
||||
#elif UAVCAN_STM32_NUTTX
|
||||
#if UAVCAN_STM32_NUTTX
|
||||
# include <nuttx/config.h>
|
||||
# include <nuttx/fs/fs.h>
|
||||
# include <poll.h>
|
||||
|
@ -16,9 +14,6 @@
|
|||
# include <cstdio>
|
||||
# include <ctime>
|
||||
# include <cstring>
|
||||
#elif UAVCAN_STM32_BAREMETAL
|
||||
#elif UAVCAN_STM32_FREERTOS
|
||||
# include <cmsis_os.h>
|
||||
#else
|
||||
# error "Unknown OS"
|
||||
#endif
|
||||
|
@ -30,36 +25,7 @@ namespace uavcan_stm32
|
|||
|
||||
class CanDriver;
|
||||
|
||||
#if UAVCAN_STM32_CHIBIOS
|
||||
|
||||
class BusEvent
|
||||
{
|
||||
chibios_rt::CounterSemaphore sem_;
|
||||
|
||||
public:
|
||||
BusEvent(CanDriver& can_driver)
|
||||
: sem_(0)
|
||||
{
|
||||
(void)can_driver;
|
||||
}
|
||||
|
||||
bool wait(uavcan::MonotonicDuration duration);
|
||||
|
||||
void signal();
|
||||
|
||||
void signalFromInterrupt();
|
||||
};
|
||||
|
||||
class Mutex
|
||||
{
|
||||
chibios_rt::Mutex mtx_;
|
||||
|
||||
public:
|
||||
void lock();
|
||||
void unlock();
|
||||
};
|
||||
|
||||
#elif UAVCAN_STM32_NUTTX
|
||||
#if UAVCAN_STM32_NUTTX
|
||||
|
||||
/**
|
||||
* All bus events are reported as POLLIN.
|
||||
|
@ -112,98 +78,6 @@ public:
|
|||
(void)pthread_mutex_unlock(&mutex_);
|
||||
}
|
||||
};
|
||||
#elif UAVCAN_STM32_BAREMETAL
|
||||
|
||||
class BusEvent
|
||||
{
|
||||
volatile bool ready;
|
||||
|
||||
public:
|
||||
BusEvent(CanDriver& can_driver)
|
||||
: ready(false)
|
||||
{
|
||||
(void)can_driver;
|
||||
}
|
||||
|
||||
bool wait(uavcan::MonotonicDuration duration)
|
||||
{
|
||||
(void)duration;
|
||||
bool lready = ready;
|
||||
#if defined ( __CC_ARM )
|
||||
return __sync_lock_test_and_set(&lready, false);
|
||||
#elif defined ( __GNUC__ )
|
||||
return __atomic_exchange_n (&lready, false, __ATOMIC_SEQ_CST);
|
||||
#else
|
||||
# error "This compiler is not supported"
|
||||
#endif
|
||||
}
|
||||
|
||||
void signal()
|
||||
{
|
||||
#if defined ( __CC_ARM )
|
||||
__sync_lock_release(&ready);
|
||||
#elif defined ( __GNUC__ )
|
||||
__atomic_store_n (&ready, true, __ATOMIC_SEQ_CST);
|
||||
#else
|
||||
# error "This compiler is not supported"
|
||||
#endif
|
||||
}
|
||||
|
||||
void signalFromInterrupt()
|
||||
{
|
||||
#if defined ( __CC_ARM )
|
||||
__sync_lock_release(&ready);
|
||||
#elif defined ( __GNUC__ )
|
||||
__atomic_store_n (&ready, true, __ATOMIC_SEQ_CST);
|
||||
#else
|
||||
# error "This compiler is not supported"
|
||||
#endif
|
||||
}
|
||||
};
|
||||
|
||||
class Mutex
|
||||
{
|
||||
public:
|
||||
void lock() { }
|
||||
void unlock() { }
|
||||
};
|
||||
|
||||
#elif UAVCAN_STM32_FREERTOS
|
||||
|
||||
class BusEvent
|
||||
{
|
||||
SemaphoreHandle_t sem_;
|
||||
BaseType_t higher_priority_task_woken;
|
||||
|
||||
public:
|
||||
BusEvent(CanDriver& can_driver)
|
||||
{
|
||||
(void)can_driver;
|
||||
sem_ = xSemaphoreCreateBinary();
|
||||
}
|
||||
|
||||
bool wait(uavcan::MonotonicDuration duration);
|
||||
|
||||
void signal();
|
||||
|
||||
void signalFromInterrupt();
|
||||
|
||||
void yieldFromISR();
|
||||
};
|
||||
|
||||
class Mutex
|
||||
{
|
||||
SemaphoreHandle_t mtx_;
|
||||
|
||||
public:
|
||||
Mutex(void)
|
||||
{
|
||||
mtx_ = xSemaphoreCreateMutex();
|
||||
}
|
||||
void lock();
|
||||
void unlock();
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
|
|
@ -6,18 +6,11 @@
|
|||
|
||||
#include <uavcan_stm32/build_config.hpp>
|
||||
|
||||
#if UAVCAN_STM32_CHIBIOS
|
||||
# include <hal.h>
|
||||
#elif UAVCAN_STM32_NUTTX
|
||||
#if UAVCAN_STM32_NUTTX
|
||||
# include <nuttx/arch.h>
|
||||
# include <arch/board/board.h>
|
||||
# include <chip/stm32_tim.h>
|
||||
# include <syslog.h>
|
||||
#elif UAVCAN_STM32_BAREMETAL
|
||||
#include <chip.h> // See http://uavcan.org/Implementations/Libuavcan/Platforms/STM32/
|
||||
#elif UAVCAN_STM32_FREERTOS
|
||||
# include <chip.h>
|
||||
# include <cmsis_os.h>
|
||||
#else
|
||||
# error "Unknown OS"
|
||||
#endif
|
||||
|
@ -38,49 +31,10 @@
|
|||
/**
|
||||
* IRQ handler macros
|
||||
*/
|
||||
#if UAVCAN_STM32_CHIBIOS
|
||||
# define UAVCAN_STM32_IRQ_HANDLER(id) CH_IRQ_HANDLER(id)
|
||||
# define UAVCAN_STM32_IRQ_PROLOGUE() CH_IRQ_PROLOGUE()
|
||||
# define UAVCAN_STM32_IRQ_EPILOGUE() CH_IRQ_EPILOGUE()
|
||||
#elif UAVCAN_STM32_NUTTX
|
||||
#if UAVCAN_STM32_NUTTX
|
||||
# define UAVCAN_STM32_IRQ_HANDLER(id) int id(int irq, FAR void* context, FAR void *arg)
|
||||
# define UAVCAN_STM32_IRQ_PROLOGUE()
|
||||
# define UAVCAN_STM32_IRQ_EPILOGUE() return 0;
|
||||
#else
|
||||
# define UAVCAN_STM32_IRQ_HANDLER(id) void id(void)
|
||||
# define UAVCAN_STM32_IRQ_PROLOGUE()
|
||||
# define UAVCAN_STM32_IRQ_EPILOGUE()
|
||||
#endif
|
||||
|
||||
#if UAVCAN_STM32_CHIBIOS
|
||||
/**
|
||||
* Priority mask for timer and CAN interrupts.
|
||||
*/
|
||||
# ifndef UAVCAN_STM32_IRQ_PRIORITY_MASK
|
||||
# if (CH_KERNEL_MAJOR == 2)
|
||||
# define UAVCAN_STM32_IRQ_PRIORITY_MASK CORTEX_PRIORITY_MASK(CORTEX_MAX_KERNEL_PRIORITY)
|
||||
# else // ChibiOS 3+
|
||||
# define UAVCAN_STM32_IRQ_PRIORITY_MASK CORTEX_MAX_KERNEL_PRIORITY
|
||||
# endif
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#if UAVCAN_STM32_BAREMETAL
|
||||
/**
|
||||
* Priority mask for timer and CAN interrupts.
|
||||
*/
|
||||
# ifndef UAVCAN_STM32_IRQ_PRIORITY_MASK
|
||||
# define UAVCAN_STM32_IRQ_PRIORITY_MASK 0
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#if UAVCAN_STM32_FREERTOS
|
||||
/**
|
||||
* Priority mask for timer and CAN interrupts.
|
||||
*/
|
||||
# ifndef UAVCAN_STM32_IRQ_PRIORITY_MASK
|
||||
# define UAVCAN_STM32_IRQ_PRIORITY_MASK configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -94,15 +48,7 @@
|
|||
|
||||
namespace uavcan_stm32
|
||||
{
|
||||
#if UAVCAN_STM32_CHIBIOS
|
||||
|
||||
struct CriticalSectionLocker
|
||||
{
|
||||
CriticalSectionLocker() { chSysSuspend(); }
|
||||
~CriticalSectionLocker() { chSysEnable(); }
|
||||
};
|
||||
|
||||
#elif UAVCAN_STM32_NUTTX
|
||||
#if UAVCAN_STM32_NUTTX
|
||||
|
||||
struct CriticalSectionLocker
|
||||
{
|
||||
|
@ -118,38 +64,6 @@ struct CriticalSectionLocker
|
|||
}
|
||||
};
|
||||
|
||||
#elif UAVCAN_STM32_BAREMETAL
|
||||
|
||||
struct CriticalSectionLocker
|
||||
{
|
||||
|
||||
CriticalSectionLocker()
|
||||
{
|
||||
__disable_irq();
|
||||
}
|
||||
|
||||
~CriticalSectionLocker()
|
||||
{
|
||||
__enable_irq();
|
||||
}
|
||||
};
|
||||
|
||||
#elif UAVCAN_STM32_FREERTOS
|
||||
|
||||
struct CriticalSectionLocker
|
||||
{
|
||||
|
||||
CriticalSectionLocker()
|
||||
{
|
||||
taskENTER_CRITICAL();
|
||||
}
|
||||
|
||||
~CriticalSectionLocker()
|
||||
{
|
||||
taskEXIT_CRITICAL();
|
||||
}
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
namespace clock
|
||||
|
|
|
@ -8,41 +8,14 @@
|
|||
#include <uavcan_stm32/clock.hpp>
|
||||
#include "internal.hpp"
|
||||
|
||||
#if UAVCAN_STM32_CHIBIOS
|
||||
# include <hal.h>
|
||||
#elif UAVCAN_STM32_NUTTX
|
||||
#if UAVCAN_STM32_NUTTX
|
||||
# include <nuttx/arch.h>
|
||||
# include <nuttx/irq.h>
|
||||
# include <arch/board/board.h>
|
||||
#elif UAVCAN_STM32_BAREMETAL
|
||||
#include <chip.h> // See http://uavcan.org/Implementations/Libuavcan/Platforms/STM32/
|
||||
#elif UAVCAN_STM32_FREERTOS
|
||||
#else
|
||||
# error "Unknown OS"
|
||||
#endif
|
||||
|
||||
#if (UAVCAN_STM32_CHIBIOS && CH_KERNEL_MAJOR == 2) || UAVCAN_STM32_BAREMETAL
|
||||
# if !(defined(STM32F10X_CL) || defined(STM32F2XX) || defined(STM32F3XX) || defined(STM32F4XX))
|
||||
// IRQ numbers
|
||||
# define CAN1_RX0_IRQn USB_LP_CAN1_RX0_IRQn
|
||||
# define CAN1_TX_IRQn USB_HP_CAN1_TX_IRQn
|
||||
// IRQ vectors
|
||||
# if !defined(CAN1_RX0_IRQHandler) || !defined(CAN1_TX_IRQHandler)
|
||||
# define CAN1_TX_IRQHandler USB_HP_CAN1_TX_IRQHandler
|
||||
# define CAN1_RX0_IRQHandler USB_LP_CAN1_RX0_IRQHandler
|
||||
# endif
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#if (UAVCAN_STM32_CHIBIOS && (CH_KERNEL_MAJOR == 3 || CH_KERNEL_MAJOR == 4 || CH_KERNEL_MAJOR == 5))
|
||||
#define CAN1_TX_IRQHandler STM32_CAN1_TX_HANDLER
|
||||
#define CAN1_RX0_IRQHandler STM32_CAN1_RX0_HANDLER
|
||||
#define CAN1_RX1_IRQHandler STM32_CAN1_RX1_HANDLER
|
||||
#define CAN2_TX_IRQHandler STM32_CAN2_TX_HANDLER
|
||||
#define CAN2_RX0_IRQHandler STM32_CAN2_RX0_HANDLER
|
||||
#define CAN2_RX1_IRQHandler STM32_CAN2_RX1_HANDLER
|
||||
#endif
|
||||
|
||||
#if UAVCAN_STM32_NUTTX
|
||||
# if !defined(STM32_IRQ_CAN1TX) && !defined(STM32_IRQ_CAN1RX0)
|
||||
# define STM32_IRQ_CAN1TX STM32_IRQ_USBHPCANTX
|
||||
|
@ -64,11 +37,6 @@ static int can2_irq(const int irq, void*, void*);
|
|||
#define CAN1_TX_IRQn CAN_TX_IRQn
|
||||
#define CAN1_RX0_IRQn CAN_RX0_IRQn
|
||||
#define CAN1_RX1_IRQn CAN_RX1_IRQn
|
||||
# if UAVCAN_STM32_BAREMETAL
|
||||
# define CAN1_TX_IRQHandler CAN_TX_IRQHandler
|
||||
# define CAN1_RX0_IRQHandler CAN_RX0_IRQHandler
|
||||
# define CAN1_RX1_IRQHandler CAN_RX1_IRQHandler
|
||||
# endif
|
||||
#endif
|
||||
|
||||
|
||||
|
@ -202,14 +170,8 @@ int CanIface::computeTimings(const uavcan::uint32_t target_bitrate, Timings& out
|
|||
/*
|
||||
* Hardware configuration
|
||||
*/
|
||||
#if UAVCAN_STM32_BAREMETAL
|
||||
const uavcan::uint32_t pclk = STM32_PCLK1;
|
||||
#elif UAVCAN_STM32_CHIBIOS
|
||||
const uavcan::uint32_t pclk = STM32_PCLK1;
|
||||
#elif UAVCAN_STM32_NUTTX
|
||||
#if UAVCAN_STM32_NUTTX
|
||||
const uavcan::uint32_t pclk = STM32_PCLK1_FREQUENCY;
|
||||
#elif UAVCAN_STM32_FREERTOS
|
||||
const uavcan::uint32_t pclk = HAL_RCC_GetPCLK1Freq();
|
||||
#else
|
||||
# error "Unknown OS"
|
||||
#endif
|
||||
|
@ -535,7 +497,7 @@ uavcan::int16_t CanIface::configureFilters(const uavcan::CanFilterConfig* filter
|
|||
|
||||
bool CanIface::waitMsrINakBitStateChange(bool target_state)
|
||||
{
|
||||
#if UAVCAN_STM32_NUTTX || UAVCAN_STM32_CHIBIOS || UAVCAN_STM32_FREERTOS
|
||||
#if UAVCAN_STM32_NUTTX
|
||||
const unsigned Timeout = 1000;
|
||||
#else
|
||||
const unsigned Timeout = 2000000;
|
||||
|
@ -549,16 +511,6 @@ bool CanIface::waitMsrINakBitStateChange(bool target_state)
|
|||
}
|
||||
#if UAVCAN_STM32_NUTTX
|
||||
::usleep(1000);
|
||||
#endif
|
||||
#if UAVCAN_STM32_CHIBIOS
|
||||
#ifdef MS2ST
|
||||
::chThdSleep(MS2ST(1));
|
||||
#else
|
||||
::chThdSleep(TIME_MS2I(1));
|
||||
#endif
|
||||
#endif
|
||||
#if UAVCAN_STM32_FREERTOS
|
||||
::osDelay(1);
|
||||
#endif
|
||||
}
|
||||
return false;
|
||||
|
@ -706,9 +658,6 @@ void CanIface::handleTxInterrupt(const uavcan::uint64_t utc_usec)
|
|||
|
||||
pollErrorFlagsFromISR();
|
||||
|
||||
#if UAVCAN_STM32_FREERTOS
|
||||
update_event_.yieldFromISR();
|
||||
#endif
|
||||
}
|
||||
|
||||
void CanIface::handleRxInterrupt(uavcan::uint8_t fifo_index, uavcan::uint64_t utc_usec)
|
||||
|
@ -773,9 +722,6 @@ void CanIface::handleRxInterrupt(uavcan::uint8_t fifo_index, uavcan::uint64_t ut
|
|||
|
||||
pollErrorFlagsFromISR();
|
||||
|
||||
#if UAVCAN_STM32_FREERTOS
|
||||
update_event_.yieldFromISR();
|
||||
#endif
|
||||
}
|
||||
|
||||
void CanIface::pollErrorFlagsFromISR()
|
||||
|
@ -957,25 +903,6 @@ uavcan::int16_t CanDriver::select(uavcan::CanSelectMasks& inout_masks,
|
|||
}
|
||||
|
||||
|
||||
#if UAVCAN_STM32_BAREMETAL || UAVCAN_STM32_FREERTOS
|
||||
|
||||
static void nvicEnableVector(IRQn_Type irq, uint8_t prio)
|
||||
{
|
||||
#if !defined (USE_HAL_DRIVER)
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
NVIC_InitStructure.NVIC_IRQChannel = irq;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = prio;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
#else
|
||||
HAL_NVIC_SetPriority(irq, prio, 0);
|
||||
HAL_NVIC_EnableIRQ(irq);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void CanDriver::initOnce()
|
||||
{
|
||||
/*
|
||||
|
@ -1024,18 +951,6 @@ void CanDriver::initOnce()
|
|||
IRQ_ATTACH(STM32_IRQ_CAN2RX1, can2_irq);
|
||||
# endif
|
||||
# undef IRQ_ATTACH
|
||||
#elif UAVCAN_STM32_CHIBIOS || UAVCAN_STM32_BAREMETAL || UAVCAN_STM32_FREERTOS
|
||||
{
|
||||
CriticalSectionLocker lock;
|
||||
nvicEnableVector(CAN1_TX_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
|
||||
nvicEnableVector(CAN1_RX0_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
|
||||
nvicEnableVector(CAN1_RX1_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
|
||||
# if UAVCAN_STM32_NUM_IFACES > 1
|
||||
nvicEnableVector(CAN2_TX_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
|
||||
nvicEnableVector(CAN2_RX0_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
|
||||
nvicEnableVector(CAN2_RX1_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
|
||||
# endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -14,21 +14,6 @@
|
|||
/*
|
||||
* Timer instance
|
||||
*/
|
||||
# if (UAVCAN_STM32_CHIBIOS && CH_KERNEL_MAJOR == 2) || UAVCAN_STM32_BAREMETAL || UAVCAN_STM32_FREERTOS
|
||||
# define TIMX UAVCAN_STM32_GLUE2(TIM, UAVCAN_STM32_TIMER_NUMBER)
|
||||
# define TIMX_IRQn UAVCAN_STM32_GLUE3(TIM, UAVCAN_STM32_TIMER_NUMBER, _IRQn)
|
||||
# define TIMX_INPUT_CLOCK STM32_TIMCLK1
|
||||
# endif
|
||||
|
||||
# if (UAVCAN_STM32_CHIBIOS && (CH_KERNEL_MAJOR == 3 || CH_KERNEL_MAJOR == 4 || CH_KERNEL_MAJOR == 5))
|
||||
# define TIMX UAVCAN_STM32_GLUE2(STM32_TIM, UAVCAN_STM32_TIMER_NUMBER)
|
||||
# define TIMX_IRQn UAVCAN_STM32_GLUE3(STM32_TIM, UAVCAN_STM32_TIMER_NUMBER, _NUMBER)
|
||||
# define TIMX_IRQHandler UAVCAN_STM32_GLUE3(STM32_TIM, UAVCAN_STM32_TIMER_NUMBER, _HANDLER)
|
||||
# define TIMX_INPUT_CLOCK STM32_TIMCLK1
|
||||
# else
|
||||
# define TIMX_IRQHandler UAVCAN_STM32_GLUE3(TIM, UAVCAN_STM32_TIMER_NUMBER, _IRQHandler)
|
||||
# endif
|
||||
|
||||
# if UAVCAN_STM32_NUTTX
|
||||
# define TIMX UAVCAN_STM32_GLUE3(STM32_TIM, UAVCAN_STM32_TIMER_NUMBER, _BASE)
|
||||
# define TMR_REG(o) (TIMX + (o))
|
||||
|
@ -94,25 +79,6 @@ uavcan::uint64_t time_utc = 0;
|
|||
|
||||
}
|
||||
|
||||
#if UAVCAN_STM32_BAREMETAL || UAVCAN_STM32_FREERTOS
|
||||
|
||||
static void nvicEnableVector(IRQn_Type irq, uint8_t prio)
|
||||
{
|
||||
#if !defined (USE_HAL_DRIVER)
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
NVIC_InitStructure.NVIC_IRQChannel = irq;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = prio;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
#else
|
||||
HAL_NVIC_SetPriority(irq, prio, 0);
|
||||
HAL_NVIC_EnableIRQ(irq);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void init()
|
||||
{
|
||||
|
@ -124,30 +90,6 @@ void init()
|
|||
initialized = true;
|
||||
|
||||
|
||||
# if UAVCAN_STM32_CHIBIOS || UAVCAN_STM32_BAREMETAL || UAVCAN_STM32_FREERTOS
|
||||
// Power-on and reset
|
||||
TIMX_RCC_ENR |= TIMX_RCC_ENR_MASK;
|
||||
TIMX_RCC_RSTR |= TIMX_RCC_RSTR_MASK;
|
||||
TIMX_RCC_RSTR &= ~TIMX_RCC_RSTR_MASK;
|
||||
|
||||
// Enable IRQ
|
||||
nvicEnableVector(TIMX_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
|
||||
|
||||
# if (TIMX_INPUT_CLOCK % 1000000) != 0
|
||||
# error "No way, timer clock must be divisible by 1e6. FIXME!"
|
||||
# endif
|
||||
|
||||
// Start the timer
|
||||
TIMX->ARR = 0xFFFF;
|
||||
TIMX->PSC = (TIMX_INPUT_CLOCK / 1000000) - 1; // 1 tick == 1 microsecond
|
||||
TIMX->CR1 = TIM_CR1_URS;
|
||||
TIMX->SR = 0;
|
||||
TIMX->EGR = TIM_EGR_UG; // Reload immediately
|
||||
TIMX->DIER = TIM_DIER_UIE;
|
||||
TIMX->CR1 = TIM_CR1_CEN; // Start
|
||||
|
||||
# endif
|
||||
|
||||
# if UAVCAN_STM32_NUTTX
|
||||
|
||||
// Attach IRQ
|
||||
|
@ -196,23 +138,6 @@ void setUtc(uavcan::UtcTime time)
|
|||
|
||||
static uavcan::uint64_t sampleUtcFromCriticalSection()
|
||||
{
|
||||
# if UAVCAN_STM32_CHIBIOS || UAVCAN_STM32_BAREMETAL || UAVCAN_STM32_FREERTOS
|
||||
UAVCAN_ASSERT(initialized);
|
||||
UAVCAN_ASSERT(TIMX->DIER & TIM_DIER_UIE);
|
||||
|
||||
volatile uavcan::uint64_t time = time_utc;
|
||||
volatile uavcan::uint32_t cnt = TIMX->CNT;
|
||||
|
||||
if (TIMX->SR & TIM_SR_UIF)
|
||||
{
|
||||
cnt = TIMX->CNT;
|
||||
const uavcan::int32_t add = uavcan::int32_t(USecPerOverflow) +
|
||||
(utc_accumulated_correction_nsec + utc_correction_nsec_per_overflow) / 1000;
|
||||
time = uavcan::uint64_t(uavcan::int64_t(time) + add);
|
||||
}
|
||||
return time + cnt;
|
||||
# endif
|
||||
|
||||
# if UAVCAN_STM32_NUTTX
|
||||
|
||||
UAVCAN_ASSERT(initialized);
|
||||
|
@ -246,14 +171,6 @@ uavcan::MonotonicTime getMonotonic()
|
|||
|
||||
volatile uavcan::uint64_t time = time_mono;
|
||||
|
||||
# if UAVCAN_STM32_CHIBIOS || UAVCAN_STM32_BAREMETAL || UAVCAN_STM32_FREERTOS
|
||||
|
||||
volatile uavcan::uint32_t cnt = TIMX->CNT;
|
||||
if (TIMX->SR & TIM_SR_UIF)
|
||||
{
|
||||
cnt = TIMX->CNT;
|
||||
# endif
|
||||
|
||||
# if UAVCAN_STM32_NUTTX
|
||||
|
||||
volatile uavcan::uint32_t cnt = getreg16(TMR_REG(STM32_BTIM_CNT_OFFSET));
|
||||
|
@ -453,9 +370,6 @@ UAVCAN_STM32_IRQ_HANDLER(TIMX_IRQHandler)
|
|||
{
|
||||
UAVCAN_STM32_IRQ_PROLOGUE();
|
||||
|
||||
# if UAVCAN_STM32_CHIBIOS || UAVCAN_STM32_BAREMETAL || UAVCAN_STM32_FREERTOS
|
||||
TIMX->SR = 0;
|
||||
# endif
|
||||
# if UAVCAN_STM32_NUTTX
|
||||
putreg16(0, TMR_REG(STM32_BTIM_SR_OFFSET));
|
||||
# endif
|
||||
|
|
|
@ -11,132 +11,7 @@
|
|||
namespace uavcan_stm32
|
||||
{
|
||||
|
||||
#if UAVCAN_STM32_CHIBIOS
|
||||
/*
|
||||
* BusEvent
|
||||
*/
|
||||
bool BusEvent::wait(uavcan::MonotonicDuration duration)
|
||||
{
|
||||
// set maximum time to allow for 16 bit timers running at 1MHz
|
||||
static const uavcan::int64_t MaxDelayUSec = 0x000FFFF;
|
||||
|
||||
const uavcan::int64_t usec = duration.toUSec();
|
||||
msg_t ret = msg_t();
|
||||
|
||||
if (usec <= 0)
|
||||
{
|
||||
# if (CH_KERNEL_MAJOR == 2)
|
||||
ret = sem_.waitTimeout(TIME_IMMEDIATE);
|
||||
# else // ChibiOS 3+
|
||||
ret = sem_.wait(TIME_IMMEDIATE);
|
||||
# endif
|
||||
}
|
||||
else
|
||||
{
|
||||
# if (CH_KERNEL_MAJOR == 2)
|
||||
ret = sem_.waitTimeout((usec > MaxDelayUSec) ? US2ST(MaxDelayUSec) : US2ST(usec));
|
||||
# elif defined(MS2ST) // ChibiOS 3+
|
||||
ret = sem_.wait((usec > MaxDelayUSec) ? US2ST(MaxDelayUSec) : US2ST(usec));
|
||||
# else // ChibiOS 17+
|
||||
ret = sem_.wait(::systime_t((usec > MaxDelayUSec) ? TIME_US2I(MaxDelayUSec) : TIME_US2I(usec)));
|
||||
# endif
|
||||
}
|
||||
# if (CH_KERNEL_MAJOR == 2)
|
||||
return ret == RDY_OK;
|
||||
# else // ChibiOS 3+
|
||||
return ret == MSG_OK;
|
||||
# endif
|
||||
}
|
||||
|
||||
void BusEvent::signal()
|
||||
{
|
||||
sem_.signal();
|
||||
}
|
||||
|
||||
void BusEvent::signalFromInterrupt()
|
||||
{
|
||||
# if (CH_KERNEL_MAJOR == 2)
|
||||
chSysLockFromIsr();
|
||||
sem_.signalI();
|
||||
chSysUnlockFromIsr();
|
||||
# else // ChibiOS 3+
|
||||
chSysLockFromISR();
|
||||
sem_.signalI();
|
||||
chSysUnlockFromISR();
|
||||
# endif
|
||||
}
|
||||
|
||||
/*
|
||||
* Mutex
|
||||
*/
|
||||
void Mutex::lock()
|
||||
{
|
||||
mtx_.lock();
|
||||
}
|
||||
|
||||
void Mutex::unlock()
|
||||
{
|
||||
# if (CH_KERNEL_MAJOR == 2)
|
||||
chibios_rt::BaseThread::unlockMutex();
|
||||
# else // ChibiOS 3+
|
||||
mtx_.unlock();
|
||||
# endif
|
||||
}
|
||||
|
||||
|
||||
#elif UAVCAN_STM32_FREERTOS
|
||||
|
||||
bool BusEvent::wait(uavcan::MonotonicDuration duration)
|
||||
{
|
||||
static const uavcan::int64_t MaxDelayMSec = 0x000FFFFF;
|
||||
|
||||
const uavcan::int64_t msec = duration.toMSec();
|
||||
|
||||
BaseType_t ret;
|
||||
|
||||
if (msec <= 0)
|
||||
{
|
||||
ret = xSemaphoreTake( sem_, ( TickType_t ) 0 );
|
||||
}
|
||||
else
|
||||
{
|
||||
ret = xSemaphoreTake( sem_, (msec > MaxDelayMSec) ? (MaxDelayMSec/portTICK_RATE_MS) : (msec/portTICK_RATE_MS));
|
||||
}
|
||||
return ret == pdTRUE;
|
||||
}
|
||||
|
||||
void BusEvent::signal()
|
||||
{
|
||||
xSemaphoreGive( sem_ );
|
||||
}
|
||||
|
||||
void BusEvent::signalFromInterrupt()
|
||||
{
|
||||
higher_priority_task_woken = pdFALSE;
|
||||
|
||||
xSemaphoreGiveFromISR( sem_, &higher_priority_task_woken );
|
||||
}
|
||||
|
||||
void BusEvent::yieldFromISR()
|
||||
{
|
||||
portYIELD_FROM_ISR( higher_priority_task_woken );
|
||||
}
|
||||
|
||||
/*
|
||||
* Mutex
|
||||
*/
|
||||
void Mutex::lock()
|
||||
{
|
||||
xSemaphoreTake( mtx_, portMAX_DELAY );
|
||||
}
|
||||
|
||||
void Mutex::unlock()
|
||||
{
|
||||
xSemaphoreGive( mtx_ );
|
||||
}
|
||||
|
||||
|
||||
#elif UAVCAN_STM32_NUTTX
|
||||
#if UAVCAN_STM32_NUTTX
|
||||
|
||||
BusEvent::BusEvent(CanDriver& can_driver)
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue