mirror of
https://git.intern.spaceteamaachen.de/ALPAKA/sta-core.git
synced 2025-08-06 10:27:34 +00:00
Added I2C support for raspi & first rework of debugging
This commit is contained in:
12
include/sta/devices/arduino/not_implemented.hpp
Normal file
12
include/sta/devices/arduino/not_implemented.hpp
Normal file
@@ -0,0 +1,12 @@
|
||||
#ifndef STA_CORE_ARDUINO_NOT_IMPLEMENTED_HPP
|
||||
#define STA_CORE_ARDUINO_NOT_IMPLEMENTED_HPP
|
||||
|
||||
|
||||
/**
|
||||
* @defgroup sta_core_arduino Arduino
|
||||
* @ingroup sta_core_platforms
|
||||
* @brief Modules implemented for the Arduino platform.
|
||||
*/
|
||||
|
||||
|
||||
#endif // STA_CORE_ARDUINO_NOT_IMPLEMENTED_HPP
|
52
include/sta/devices/raspi/bus/i2c.hpp
Normal file
52
include/sta/devices/raspi/bus/i2c.hpp
Normal file
@@ -0,0 +1,52 @@
|
||||
#ifndef STA_RASPI_I2C_HPP
|
||||
#define STA_RASPI_I2C_HPP
|
||||
|
||||
#include <sta/config.hpp>
|
||||
#ifdef STA_PLATFORM_RASPI
|
||||
|
||||
#include <sta/bus/i2c/i2c.hpp>
|
||||
#include <sta/bus/i2c/device.hpp>
|
||||
|
||||
#include <linux/i2c-dev.h>
|
||||
#include <sys/ioctl.h>
|
||||
|
||||
namespace sta
|
||||
{
|
||||
enum class I2cNode {
|
||||
DEV_1,
|
||||
DEV_2
|
||||
};
|
||||
|
||||
class RaspiI2c : public I2c
|
||||
{
|
||||
public:
|
||||
RaspiI2c(I2cNode node, Mutex * mutex=nullptr, bool persistent_open=false);
|
||||
~RaspiI2c();
|
||||
|
||||
void transfer(uint8_t value) override;
|
||||
void transfer16(uint16_t value) override;
|
||||
void transfer(const uint8_t * buffer, size_t size) override;
|
||||
void transfer(const uint8_t * txBuffer, uint8_t * rxBuffer, size_t size) override;
|
||||
void receive(uint8_t * buffer, size_t size) override;
|
||||
|
||||
void fill(uint8_t value, size_t count) override;
|
||||
|
||||
void selectAddress(uint16_t address) override;
|
||||
void acquire() override;
|
||||
void release() override;
|
||||
private:
|
||||
char * i2cdev_;
|
||||
int i2cfd_;
|
||||
bool open_ = false;
|
||||
const bool persistent_open_;
|
||||
};
|
||||
|
||||
class RaspiI2cDevice : public I2cDevice
|
||||
{
|
||||
RaspiI2cDevice(I2c * intf, uint16_t address_10bit, Mutex* mutex=nullptr, bool master=false, bool blocking=true);
|
||||
};
|
||||
} // namespace sta
|
||||
|
||||
#endif // STA_PLATFORM_RASPI
|
||||
|
||||
#endif // STA_I2C_HPP
|
60
include/sta/devices/raspi/bus/spi.hpp
Normal file
60
include/sta/devices/raspi/bus/spi.hpp
Normal file
@@ -0,0 +1,60 @@
|
||||
#ifndef STA_CORE_RASPI_SPI_HPP
|
||||
#define STA_CORE_RASPI_SPI_HPP
|
||||
|
||||
#include <sta/config.hpp>
|
||||
#ifdef STA_PLATFORM_RASPI
|
||||
|
||||
#include <sta/bus/spi/device.hpp>
|
||||
#include <sta/bus/spi/spi.hpp>
|
||||
|
||||
namespace sta
|
||||
{
|
||||
enum class SPINode {
|
||||
DEV_0_0,
|
||||
DEV_0_1
|
||||
};
|
||||
|
||||
class RaspiSPI : public SPI
|
||||
{
|
||||
public:
|
||||
RaspiSPI(SPINode node, const SPISettings & settings, Mutex * mutex = nullptr, bool persistent_open = true);
|
||||
~RaspiSPI();
|
||||
|
||||
void transfer(uint8_t value) override;
|
||||
void transfer16(uint16_t value) override;
|
||||
void transfer(const uint8_t * buffer, size_t size) override;
|
||||
void transfer(const uint8_t * txBuffer, uint8_t * rxBuffer, size_t size) override;
|
||||
void receive(uint8_t * buffer, size_t size) override;
|
||||
|
||||
void fill(uint8_t value, size_t count) override;
|
||||
|
||||
void acquire() override;
|
||||
void release() override;
|
||||
|
||||
private:
|
||||
char * spidev_;
|
||||
int spifd_;
|
||||
bool open_;
|
||||
const bool persistent_open_;
|
||||
SPISettings settings_;
|
||||
|
||||
uint8_t mode_;
|
||||
uint8_t dataSize_;
|
||||
uint8_t bitOrder_;
|
||||
uint32_t clkSpeed_;
|
||||
|
||||
void update_setting(int setting, int value);
|
||||
void get_setting(int setting, void * rslt_ptr);
|
||||
void update_settings();
|
||||
};
|
||||
|
||||
class RaspiSPIDevice : public SPIDevice
|
||||
{
|
||||
public:
|
||||
RaspiSPIDevice(RaspiSPI * intf);
|
||||
};
|
||||
} // namespace sta
|
||||
|
||||
#endif // STA_PLATFORM_RASPI
|
||||
|
||||
#endif // STA_CORE_RASPI_HPP
|
0
include/sta/devices/raspi/can.hpp
Normal file
0
include/sta/devices/raspi/can.hpp
Normal file
44
include/sta/devices/raspi/delay.hpp
Normal file
44
include/sta/devices/raspi/delay.hpp
Normal file
@@ -0,0 +1,44 @@
|
||||
/**
|
||||
* @file
|
||||
* @brief Delay functions.
|
||||
*
|
||||
* Configuration:
|
||||
* * STA_RASPI_DELAY_US_TIM: 1 MHz TIM instance used by sta::delayUs
|
||||
*
|
||||
* NOTE: TIM time base must be started before use of sta::delayUs by calling sta::initHAL.
|
||||
* When using startup system task this is handled automatically.
|
||||
*/
|
||||
#ifndef STA_CORE_RASPI_DELAY_HPP
|
||||
#define STA_CORE_RASPI_DELAY_HPP
|
||||
|
||||
|
||||
// Only enable module on RASPI platform
|
||||
#include <sta/config.hpp>
|
||||
|
||||
|
||||
#if defined(STA_PLATFORM_RASPI) || defined(DOXYGEN)
|
||||
|
||||
#include <cstdint>
|
||||
|
||||
|
||||
namespace sta
|
||||
{
|
||||
/**
|
||||
* @brief Millisecond delay.
|
||||
*
|
||||
* @param ms Milliseconds
|
||||
*/
|
||||
void delayMs(uint32_t ms);
|
||||
|
||||
/**
|
||||
* @brief Microsecond delay.
|
||||
*
|
||||
* @param us Microseconds
|
||||
*/
|
||||
void delayUs(uint32_t us);
|
||||
} // namespace sta
|
||||
|
||||
|
||||
#endif // STA_PLATFORM_RASPI
|
||||
|
||||
#endif // STA_CORE_RASPI_DELAY_HPP
|
46
include/sta/devices/raspi/gpio_pin.hpp
Normal file
46
include/sta/devices/raspi/gpio_pin.hpp
Normal file
@@ -0,0 +1,46 @@
|
||||
#ifndef STA_CORE_RASPI_GPIO_PIN_HPP
|
||||
#define STA_CORE_RASPI_GPIO_PIN_HPP
|
||||
|
||||
// Only enable module on Raspi platform w/ HAL GPIO module enabled
|
||||
#include <sta/config.hpp>
|
||||
#ifdef STA_PLATFORM_RASPI
|
||||
# include <sta/devices/raspi/hal.hpp>
|
||||
# define STA_RASPI_GPIO_ENABLED
|
||||
#endif // STA_PLATFORM_RASPI
|
||||
|
||||
#if defined(STA_RASPI_GPIO_ENABLED) || defined(DOXYGEN)
|
||||
|
||||
#include <sta/gpio_pin.hpp>
|
||||
#include <cstdint>
|
||||
|
||||
namespace sta
|
||||
{
|
||||
enum class GpioMode {
|
||||
GPIO_OUTPUT,
|
||||
GPIO_INPUT
|
||||
};
|
||||
|
||||
class RaspiGpioPin : public GpioPin
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* @param pin Pin index
|
||||
* @param mode The mode of the GPIO pin. Either INPUT or OUTPUT
|
||||
*/
|
||||
RaspiGpioPin(uint8_t pin, GpioMode mode);
|
||||
|
||||
void setState(GpioPinState state) override;
|
||||
|
||||
GpioPinState getState() override;
|
||||
|
||||
static RaspiGpioPin * DUMMY_GPIO;
|
||||
|
||||
private:
|
||||
uint8_t pin_;
|
||||
GpioMode mode_;
|
||||
};
|
||||
} // namespace sta
|
||||
|
||||
#endif // STA_RASPI_GPIO_ENABLED
|
||||
|
||||
#endif // STA_CORE_RASPI_GPIO_PIN_HPP
|
8
include/sta/devices/raspi/hal.hpp
Normal file
8
include/sta/devices/raspi/hal.hpp
Normal file
@@ -0,0 +1,8 @@
|
||||
#ifndef STA_CORE_RASPI_HAL_HPP
|
||||
#define STA_CORE_RASPI_HAL_HPP
|
||||
|
||||
#include <wiringPi.h>
|
||||
#include <stdio.h>
|
||||
#include <sys/ioctl.h>
|
||||
|
||||
#endif //STA_CORE_RASPI_HAL_HPP
|
13
include/sta/devices/raspi/mcu/common.hpp
Normal file
13
include/sta/devices/raspi/mcu/common.hpp
Normal file
@@ -0,0 +1,13 @@
|
||||
/**
|
||||
* @file
|
||||
* @brief Common configuration for Raspberry Pi MCUs
|
||||
*/
|
||||
#ifndef STA_CORE_RASPI_MCU_COMMON_HPP
|
||||
#define STA_CORE_RASPI_MCU_COMMON_HPP
|
||||
|
||||
#define STA_MCU_LITTLE_ENDIAN
|
||||
|
||||
// Enable STM32 platform
|
||||
#define STA_PLATFORM_RASPI
|
||||
|
||||
#endif // STA_CORE_RASPI_MCU_COMMON_HPP
|
120
include/sta/devices/stm32/can.hpp
Normal file
120
include/sta/devices/stm32/can.hpp
Normal file
@@ -0,0 +1,120 @@
|
||||
/**
|
||||
* @file
|
||||
* @brief Implementation of CanController using STM32 HAL.
|
||||
*
|
||||
* Configuration:
|
||||
* * STA_STM32_CAN_GLOBAL: Create global CanBus object using this CAN instance
|
||||
*/
|
||||
#ifndef STA_CORE_STM32_CAN_HPP
|
||||
#define STA_CORE_STM32_CAN_HPP
|
||||
|
||||
/**
|
||||
* @defgroup sta_core_stm32_can CAN
|
||||
* @ingroup sta_core_stm32
|
||||
* @brief STM32 CAN module.
|
||||
*
|
||||
* Check @ref stm32BuildConfig for configuration options.
|
||||
*/
|
||||
|
||||
// Only enable module on STM32 platform w/ HAL CAN module enabled
|
||||
#include <sta/config.hpp>
|
||||
#ifdef STA_PLATFORM_STM32
|
||||
# include <sta/stm32/hal.hpp>
|
||||
# ifdef HAL_CAN_MODULE_ENABLED
|
||||
# define STA_STM32_CAN_ENABLED
|
||||
# endif // HAL_CAN_MODULE_ENABLED
|
||||
#endif // STA_PLATFORM_STM32
|
||||
|
||||
|
||||
#if defined(STA_STM32_CAN_ENABLED) || defined(DOXYGEN)
|
||||
|
||||
#include <sta/can/controller.hpp>
|
||||
|
||||
|
||||
namespace sta
|
||||
{
|
||||
/**
|
||||
* @brief Implementation of CanController interface using HAL.
|
||||
*
|
||||
* @ingroup sta_core_stm32_can
|
||||
*/
|
||||
class STM32CanController : public CanController
|
||||
{
|
||||
public:
|
||||
static constexpr uint8_t MAX_FILTER_COUNT = 14; /**< Max number of filters */
|
||||
static constexpr uint8_t MAX_FIFO_COUNT = 2; /**< Max number of FIFOs */
|
||||
static constexpr uint8_t MAX_PAYLOAD_SIZE = 8; /**< Maximum payload size */
|
||||
|
||||
public:
|
||||
/**
|
||||
* @param handle CAN handle
|
||||
*/
|
||||
STM32CanController(CAN_HandleTypeDef * handle);
|
||||
|
||||
/**
|
||||
* @brief Enable RX pending interrupts.
|
||||
*/
|
||||
void enableRxInterrupts();
|
||||
|
||||
/**
|
||||
* @brief Start CAN controller.
|
||||
*/
|
||||
void start();
|
||||
/**
|
||||
* @brief Stop CAN controller.
|
||||
*/
|
||||
void stop();
|
||||
|
||||
|
||||
// RX/TX
|
||||
//
|
||||
|
||||
bool sendFrame(const CanTxHeader & header, const uint8_t * payload) override;
|
||||
bool receiveFrame(uint8_t fifo, CanRxHeader * header, uint8_t * payload) override;
|
||||
|
||||
uint32_t getRxFifoFlags() override;
|
||||
|
||||
// RX Filter
|
||||
//
|
||||
|
||||
void configureFilter(uint8_t idx, const CanFilter & filter, bool active = false) override;
|
||||
void enableFilter(uint8_t idx) override;
|
||||
void disableFilter(uint8_t idx) override;
|
||||
void clearFilters() override;
|
||||
|
||||
private:
|
||||
/**
|
||||
* @brief Initialize filter settings.
|
||||
*/
|
||||
void initFilters();
|
||||
|
||||
private:
|
||||
CAN_HandleTypeDef * handle_; /**< CAN handle */
|
||||
CAN_FilterTypeDef filters_[MAX_FILTER_COUNT]; /**< Filter settings */
|
||||
};
|
||||
|
||||
|
||||
|
||||
#if defined(STA_STM32_CAN_GLOBAL) || DOXYGEN
|
||||
/**
|
||||
* @brief Global CAN instance.
|
||||
*
|
||||
* @ingroup sta_core_stm32_can
|
||||
*/
|
||||
extern STM32CanController CanBus;
|
||||
|
||||
/**
|
||||
* @brief Interrupt handler for pending RX frames.
|
||||
*
|
||||
* May be implemented by application.
|
||||
*
|
||||
* @ingroup sta_core_stm32_can
|
||||
*/
|
||||
void CanBus_RxPendingCallback();
|
||||
#endif // STA_STM32_CAN_GLOBAL
|
||||
} // namespace sta
|
||||
|
||||
|
||||
#endif // STA_STM32_CAN_ENABLED
|
||||
|
||||
#endif // STA_CORE_STM32_CAN_HPP
|
107
include/sta/devices/stm32/clocks.hpp
Normal file
107
include/sta/devices/stm32/clocks.hpp
Normal file
@@ -0,0 +1,107 @@
|
||||
/**
|
||||
* @file
|
||||
* @brief Helper macros for STM32 clock queries.
|
||||
*/
|
||||
#ifndef STA_CORE_STM32_CLOCKS_HPP
|
||||
#define STA_CORE_STM32_CLOCKS_HPP
|
||||
|
||||
|
||||
// Only enable module on STM32 platform
|
||||
#include <sta/config.hpp>
|
||||
|
||||
|
||||
#if defined(STA_PLATFORM_STM32) || defined(DOXYGEN)
|
||||
|
||||
#include <sta/stm32/hal.hpp>
|
||||
|
||||
|
||||
/**
|
||||
* @defgroup sta_core_stm32_clocks Clocks
|
||||
* @ingroup sta_core_stm32
|
||||
* @brief STM32 Clock queries.
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
namespace sta
|
||||
{
|
||||
/**
|
||||
* @brief Get peripheral clock frequency.
|
||||
*
|
||||
* @return Clock frequency
|
||||
*/
|
||||
using PCLKFreqFn = uint32_t (*)();
|
||||
} // namespace sta
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get function returning PCLK frequency.
|
||||
*
|
||||
* @param n Index of peripheral clock
|
||||
*/
|
||||
#define STA_STM32_GET_PCLK_FREQ_FN(n) HAL_RCC_GetPCLK ## n ## Freq
|
||||
|
||||
|
||||
/**
|
||||
* @brief Internal helper for macro expansion.
|
||||
*
|
||||
* @param n PCLK index
|
||||
* @return Function returning PCLK frequency
|
||||
*/
|
||||
#define _STA_STM32_GET_PCLK_FREQ_FN(n) STA_STM32_GET_PCLK_FREQ_FN(n)
|
||||
/**
|
||||
* @brief Map instance name to PCLK index.
|
||||
*
|
||||
* @param type Hardware type
|
||||
* @param idx Instance index
|
||||
* @return PCLK index
|
||||
*/
|
||||
#define _STA_STM32_PCLK_IDX_MAP(type, idx) STA_STM32_ ## type ## _ ## idx ## _PCLK_IDX
|
||||
// Get HAL handle to PCLK index map macro
|
||||
/**
|
||||
* @brief Map instance handle to PCLK index.
|
||||
*
|
||||
* @param handle HAL handle
|
||||
* @return PCLK index
|
||||
*/
|
||||
#define _STA_STM32_HANDLE_PCLK_IDX_MAP(handle) STA_STM32_ ## handle ## _PCLK_IDX
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get function returning frequency of PCLK used by TIM.
|
||||
*
|
||||
* @param n TIM index
|
||||
*/
|
||||
#define STA_STM32_GET_TIM_PCLK_FREQ_FN(n) _STA_STM32_GET_PCLK_FREQ_FN(_STA_STM32_PCLK_IDX_MAP(TIM, n))
|
||||
/**
|
||||
* @brief Get function returning frequency of PCLK used by SPI interface.
|
||||
*
|
||||
* @param n SPI interface index
|
||||
*/
|
||||
#define STA_STM32_GET_SPI_PCLK_FREQ_FN(n) _STA_STM32_GET_PCLK_FREQ_FN(_STA_STM32_PCLK_IDX_MAP(SPI, n))
|
||||
/**
|
||||
* @brief Get function returning frequency of PCLK used by I2C interface.
|
||||
*
|
||||
* @param n I2C interface index
|
||||
*/
|
||||
#define STA_STM32_GET_I2C_PCLK_FREQ_FN(n) _STA_STM32_GET_PCLK_FREQ_FN(_STA_STM32_PCLK_IDX_MAP(I2C, n))
|
||||
/**
|
||||
* @brief Get function returning frequency of PCLK used by USART interface.
|
||||
*
|
||||
* @param n USART interface index
|
||||
*/
|
||||
#define STA_STM32_GET_USART_PCLK_FREQ_FN(n) _STA_STM32_GET_PCLK_FREQ_FN(_STA_STM32_PCLK_IDX_MAP(USART, n))
|
||||
|
||||
/**
|
||||
* @brief Get function returning frequency of PCLK used by HAL instance.
|
||||
*
|
||||
* @param handle Instance handle
|
||||
*/
|
||||
#define STA_STM32_GET_HANDLE_PCLK_FREQ_FN(handle) _STA_STM32_GET_PCLK_FREQ_FN(_STA_STM32_HANDLE_PCLK_IDX_MAP(handle))
|
||||
|
||||
|
||||
/** @} */
|
||||
|
||||
#endif // STA_PLATFORM_STM32
|
||||
|
||||
#endif // STA_CORE_STM32_CLOCKS_HPP
|
57
include/sta/devices/stm32/delay.hpp
Normal file
57
include/sta/devices/stm32/delay.hpp
Normal file
@@ -0,0 +1,57 @@
|
||||
/**
|
||||
* @file
|
||||
* @brief Delay functions.
|
||||
*
|
||||
* Configuration:
|
||||
* * STA_STM32_DELAY_US_TIM: 1 MHz TIM instance used by sta::delayUs
|
||||
*
|
||||
* NOTE: TIM time base must be started before use of sta::delayUs by calling sta::initHAL.
|
||||
* When using startup system task this is handled automatically.
|
||||
*/
|
||||
#ifndef STA_CORE_STM32_DELAY_HPP
|
||||
#define STA_CORE_STM32_DELAY_HPP
|
||||
|
||||
|
||||
// Only enable module on STM32 platform
|
||||
#include <sta/config.hpp>
|
||||
|
||||
|
||||
#if defined(STA_PLATFORM_STM32) || defined(DOXYGEN)
|
||||
|
||||
#include <cstdint>
|
||||
|
||||
|
||||
namespace sta
|
||||
{
|
||||
/**
|
||||
* @defgroup sta_core_stm32_delay Delay
|
||||
* @ingroup sta_core_stm32
|
||||
* @brief STM32 Delay module.
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/**
|
||||
* @brief Millisecond delay.
|
||||
*
|
||||
* @param ms Milliseconds
|
||||
*/
|
||||
void delayMs(uint32_t ms);
|
||||
|
||||
#if defined(STA_STM32_DELAY_US_TIM) || defined(DOXYGEN)
|
||||
/**
|
||||
* @brief Microsecond delay.
|
||||
*
|
||||
* @param us Microseconds
|
||||
*/
|
||||
void delayUs(uint32_t us);
|
||||
#endif // STA_STM32_DELAY_US_TIM
|
||||
|
||||
|
||||
/** @} */
|
||||
} // namespace sta
|
||||
|
||||
|
||||
#endif // STA_PLATFORM_STM32
|
||||
|
||||
#endif // STA_CORE_STM32_DELAY_HPP
|
113
include/sta/devices/stm32/gpio_pin.hpp
Normal file
113
include/sta/devices/stm32/gpio_pin.hpp
Normal file
@@ -0,0 +1,113 @@
|
||||
/**
|
||||
* @file
|
||||
* @brief Wrapper for STM32 GPIO pins.
|
||||
*/
|
||||
#ifndef STA_CORE_STM32_GPIO_PIN_HPP
|
||||
#define STA_CORE_STM32_GPIO_PIN_HPP
|
||||
|
||||
|
||||
// Only enable module on STM32 platform w/ HAL GPIO module enabled
|
||||
#include <sta/config.hpp>
|
||||
#ifdef STA_PLATFORM_STM32
|
||||
# include <sta/stm32/hal.hpp>
|
||||
# ifdef HAL_GPIO_MODULE_ENABLED
|
||||
# define STA_STM32_GPIO_ENABLED
|
||||
# endif // HAL_GPIO_MODULE_ENABLED
|
||||
#endif // STA_PLATFORM_STM32
|
||||
|
||||
|
||||
#if defined(STA_STM32_GPIO_ENABLED) || defined(DOXYGEN)
|
||||
|
||||
#include <sta/gpio_pin.hpp>
|
||||
|
||||
|
||||
/**
|
||||
* @defgroup sta_core_stm32_gpio GPIO
|
||||
* @ingroup sta_core_stm32
|
||||
* @brief STM32 GPIO module.
|
||||
*/
|
||||
|
||||
|
||||
namespace sta
|
||||
{
|
||||
/**
|
||||
* @ingroup sta_core_stm32_gpio
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/**
|
||||
* @brief Container for STM GPIO Pin data.
|
||||
*/
|
||||
class STM32GpioPin : public GpioPin
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* @param port GPIO port
|
||||
* @param pin Pin index
|
||||
*/
|
||||
STM32GpioPin(GPIO_TypeDef * port, uint16_t pin);
|
||||
|
||||
void setState(GpioPinState state) override;
|
||||
|
||||
/**
|
||||
* @brief Get GPIO port for pin.
|
||||
*
|
||||
* @return GPIO port
|
||||
*/
|
||||
GPIO_TypeDef * getPort() const;
|
||||
/**
|
||||
* @brief Get pin index for pin.
|
||||
*
|
||||
* @return Pin index
|
||||
*/
|
||||
uint16_t getPin() const;
|
||||
/**
|
||||
* @brief Get GPIO port index for pin.
|
||||
*
|
||||
* @return GPIO port index
|
||||
*/
|
||||
uint8_t getPortIndex() const;
|
||||
|
||||
private:
|
||||
GPIO_TypeDef * port_; /**< GPIO port */
|
||||
uint16_t pin_; /**< GPIO pin */
|
||||
};
|
||||
|
||||
|
||||
/**
|
||||
* @brief Interrupt trigger edge.
|
||||
*/
|
||||
enum class InterruptEdge
|
||||
{
|
||||
RISING, /**< Rising edge */
|
||||
FALLING, /**< Falling edge */
|
||||
BOTH /**< Rising and falling edge */
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Check pin EXIT pin configuration.
|
||||
*
|
||||
* @param pin GPIO pin
|
||||
* @param edge Interrupt trigger edge
|
||||
* @return True if EXIT pin and trigger edge matches
|
||||
*/
|
||||
bool isInterruptEdge(const STM32GpioPin & pin, InterruptEdge edge);
|
||||
|
||||
|
||||
/** @} */
|
||||
} // namespace sta
|
||||
|
||||
/**
|
||||
* @brief Create STM32GpioPin object from pin label.
|
||||
*
|
||||
* @param label Pin label
|
||||
*
|
||||
* @ingroup sta_core_stm32_gpio
|
||||
*/
|
||||
#define STA_STM32_GPIO_PIN(label) sta::STM32GpioPin{label##_GPIO_Port, label##_Pin}
|
||||
|
||||
|
||||
#endif // STA_STM32_GPIO_ENABLED
|
||||
|
||||
#endif // STA_CORE_STM32_GPIO_PIN_HPP
|
26
include/sta/devices/stm32/hal.hpp
Normal file
26
include/sta/devices/stm32/hal.hpp
Normal file
@@ -0,0 +1,26 @@
|
||||
/**
|
||||
* @file
|
||||
* @brief Generic header for including the STM32 HAL headers.
|
||||
*/
|
||||
#ifndef STA_CORE_STM32_HAL_HPP
|
||||
#define STA_CORE_STM32_HAL_HPP
|
||||
|
||||
|
||||
/**
|
||||
* @defgroup sta_core_stm32 STM32
|
||||
* @ingroup sta_core_platforms
|
||||
* @brief Modules implemented for the STM32 platform.
|
||||
*/
|
||||
|
||||
#include <sta/config.hpp>
|
||||
#ifdef STA_PLATFORM_STM32
|
||||
|
||||
// Include STM32 HAL headers
|
||||
#include <main.h>
|
||||
|
||||
#else // !STA_PLATFORM_STM32
|
||||
# warning "Included STM32 HAL on non-STM32 platform!"
|
||||
#endif // !STA_PLATFORM_STM32
|
||||
|
||||
|
||||
#endif // STA_CORE_STM32_HAL_HPP
|
39
include/sta/devices/stm32/i2c.hpp
Normal file
39
include/sta/devices/stm32/i2c.hpp
Normal file
@@ -0,0 +1,39 @@
|
||||
#ifndef STA_STM32_I2C_HPP
|
||||
#define STA_STM32_I2C_HPP
|
||||
|
||||
#include <sta/config.hpp>
|
||||
#ifdef STA_PLATFORM_STM32
|
||||
# include <sta/stm32/hal.hpp>
|
||||
# ifdef HAL_I2C_MODULE_ENABLED
|
||||
# define STA_STM32_I2C_ENABLED
|
||||
# endif // HAL_SPI_MODULE_ENABLED
|
||||
#endif // STA_PLATFORM_STM32
|
||||
|
||||
#ifdef STA_STM32_I2C_ENABLED
|
||||
|
||||
#include <sta/i2c.hpp>
|
||||
|
||||
namespace sta {
|
||||
class STM32I2cDevice : public I2cDevice {
|
||||
private:
|
||||
I2C_HandleTypeDef* i2cHandle;
|
||||
const uint32_t timeout = HAL_MAX_DELAY;
|
||||
|
||||
public:
|
||||
STM32I2cDevice(
|
||||
I2C_HandleTypeDef* i2cHandle,
|
||||
uint16_t address,
|
||||
Mutex* mutex=nullptr,
|
||||
bool master=false,
|
||||
bool blocking=true
|
||||
);
|
||||
|
||||
bool transmit(uint8_t* data, uint16_t size) override;
|
||||
bool receive(uint8_t* data, uint16_t size) override;
|
||||
|
||||
bool deviceReady();
|
||||
};
|
||||
}
|
||||
|
||||
#endif // STA_STM32_I2C_ENABLED
|
||||
#endif // STA_STM32_I2C_HPP
|
20
include/sta/devices/stm32/init.hpp
Normal file
20
include/sta/devices/stm32/init.hpp
Normal file
@@ -0,0 +1,20 @@
|
||||
/**
|
||||
* @file
|
||||
* @brief Global STM32 HAL initialization.
|
||||
*/
|
||||
#ifndef STA_CORE_STM32_INIT_HPP
|
||||
#define STA_CORE_STM32_INIT_HPP
|
||||
|
||||
|
||||
namespace sta
|
||||
{
|
||||
/**
|
||||
* @brief Initialize global HAL objects.
|
||||
*
|
||||
* @ingroup sta_core_stm32
|
||||
*/
|
||||
void initHAL();
|
||||
} // namespace sta
|
||||
|
||||
|
||||
#endif // STA_CORE_STM32_INIT_HPP
|
78
include/sta/devices/stm32/mcu/STM32F411xE.hpp
Normal file
78
include/sta/devices/stm32/mcu/STM32F411xE.hpp
Normal file
@@ -0,0 +1,78 @@
|
||||
/**
|
||||
* @file
|
||||
* @brief Configuration for STM32F411xE family.
|
||||
*/
|
||||
#ifndef STA_CORE_STM32_MCU_STM32F411xE_HPP
|
||||
#define STA_CORE_STM32_MCU_STM32F411xE_HPP
|
||||
|
||||
|
||||
#ifndef STM32F411xE
|
||||
# error "MCU config incompatible"
|
||||
#endif // !STM32F411xE
|
||||
|
||||
|
||||
#include <sta/stm32/mcu/common.hpp>
|
||||
|
||||
|
||||
// Peripheral clock mappings
|
||||
//
|
||||
|
||||
// TIM to PCLK
|
||||
#define STA_STM32_TIM_1_PCLK_IDX 2
|
||||
#define STA_STM32_TIM_2_PCLK_IDX 1
|
||||
#define STA_STM32_TIM_3_PCLK_IDX 1
|
||||
#define STA_STM32_TIM_4_PCLK_IDX 1
|
||||
#define STA_STM32_TIM_5_PCLK_IDX 1
|
||||
#define STA_STM32_TIM_9_PCLK_IDX 2
|
||||
#define STA_STM32_TIM_10_PCLK_IDX 2
|
||||
#define STA_STM32_TIM_11_PCLK_IDX 2
|
||||
|
||||
// SPI to PCLK
|
||||
#define STA_STM32_SPI_1_PCLK_IDX 2
|
||||
#define STA_STM32_SPI_2_PCLK_IDX 1
|
||||
#define STA_STM32_SPI_3_PCLK_IDX 1
|
||||
#define STA_STM32_SPI_4_PCLK_IDX 2
|
||||
#define STA_STM32_SPI_5_PCLK_IDX 2
|
||||
|
||||
// I2C to PCLK
|
||||
#define STA_STM32_I2C_1_PCLK_IDX 1
|
||||
#define STA_STM32_I2C_2_PCLK_IDX 1
|
||||
#define STA_STM32_I2C_3_PCLK_IDX 1
|
||||
|
||||
// USART to PCLK
|
||||
#define STA_STM32_USART_1_PCLK_IDX 2
|
||||
#define STA_STM32_USART_2_PCLK_IDX 1
|
||||
#define STA_STM32_USART_6_PCLK_IDX 2
|
||||
|
||||
|
||||
// HAL handle mappings
|
||||
//
|
||||
|
||||
#define STA_STM32_htim1_PCLK_IDX STA_STM32_TIM_1_PCLK_IDX
|
||||
#define STA_STM32_htim2_PCLK_IDX STA_STM32_TIM_2_PCLK_IDX
|
||||
#define STA_STM32_htim3_PCLK_IDX STA_STM32_TIM_3_PCLK_IDX
|
||||
#define STA_STM32_htim4_PCLK_IDX STA_STM32_TIM_4_PCLK_IDX
|
||||
#define STA_STM32_htim5_PCLK_IDX STA_STM32_TIM_5_PCLK_IDX
|
||||
#define STA_STM32_htim9_PCLK_IDX STA_STM32_TIM_9_PCLK_IDX
|
||||
#define STA_STM32_htim10_PCLK_IDX STA_STM32_TIM_10_PCLK_IDX
|
||||
#define STA_STM32_htim11_PCLK_IDX STA_STM32_TIM_11_PCLK_IDX
|
||||
|
||||
// SPI to PCLK
|
||||
#define STA_STM32_hspi1_PCLK_IDX STA_STM32_SPI_1_PCLK_IDX
|
||||
#define STA_STM32_hspi2_PCLK_IDX STA_STM32_SPI_2_PCLK_IDX
|
||||
#define STA_STM32_hspi3_PCLK_IDX STA_STM32_SPI_3_PCLK_IDX
|
||||
#define STA_STM32_hspi4_PCLK_IDX STA_STM32_SPI_4_PCLK_IDX
|
||||
#define STA_STM32_hspi5_PCLK_IDX STA_STM32_SPI_5_PCLK_IDX
|
||||
|
||||
// I2C to PCLK
|
||||
#define STA_STM32_hi2c1_PCLK_IDX STA_STM32_I2C_1_PCLK_IDX
|
||||
#define STA_STM32_hi2c2_PCLK_IDX STA_STM32_I2C_2_PCLK_IDX
|
||||
#define STA_STM32_h12c3_PCLK_IDX STA_STM32_I2C_3_PCLK_IDX
|
||||
|
||||
// USART to PCLK
|
||||
#define STA_STM32_husart1_PCLK_IDX STA_STM32_USART_1_PCLK_IDX
|
||||
#define STA_STM32_husart2_PCLK_IDX STA_STM32_USART_2_PCLK_IDX
|
||||
#define STA_STM32_husart6_PCLK_IDX STA_STM32_USART_6_PCLK_IDX
|
||||
|
||||
|
||||
#endif // STA_CORE_STM32_MCU_STM32F411xE_HPP
|
17
include/sta/devices/stm32/mcu/STM32F413xx.hpp
Normal file
17
include/sta/devices/stm32/mcu/STM32F413xx.hpp
Normal file
@@ -0,0 +1,17 @@
|
||||
/**
|
||||
* @file
|
||||
* @brief Configuration for STM32F413xx family.
|
||||
*/
|
||||
#ifndef STA_CORE_STM32_MCU_STM32F413xx_HPP
|
||||
#define STA_CORE_STM32_MCU_STM32F413xx_HPP
|
||||
|
||||
|
||||
#ifndef STM32F413xx
|
||||
# error "MCU config incompatible"
|
||||
#endif // !STM32F413xx
|
||||
|
||||
|
||||
#include <sta/stm32/mcu/common.hpp>
|
||||
|
||||
|
||||
#endif // STA_CORE_STM32_MCU_STM32F413xx_HPP
|
17
include/sta/devices/stm32/mcu/common.hpp
Normal file
17
include/sta/devices/stm32/mcu/common.hpp
Normal file
@@ -0,0 +1,17 @@
|
||||
/**
|
||||
* @file
|
||||
* @brief Common configuration for STM32 MCUs
|
||||
*/
|
||||
#ifndef STA_CORE_STM32_MCU_COMMON_HPP
|
||||
#define STA_CORE_STM32_MCU_COMMON_HPP
|
||||
|
||||
|
||||
// TODO: Are all STM32 MCUs little endian?
|
||||
#define STA_MCU_LITTLE_ENDIAN
|
||||
|
||||
|
||||
// Enable STM32 platform
|
||||
#define STA_PLATFORM_STM32
|
||||
|
||||
|
||||
#endif // STA_CORE_STM32_MCU_COMMON_HPP
|
139
include/sta/devices/stm32/spi.hpp
Normal file
139
include/sta/devices/stm32/spi.hpp
Normal file
@@ -0,0 +1,139 @@
|
||||
/**
|
||||
* @file
|
||||
* @brief SPI bus implementation using STM32 HAL.
|
||||
*/
|
||||
#ifndef STA_CORE_STM32_SPI_HPP
|
||||
#define STA_CORE_STM32_SPI_HPP
|
||||
|
||||
|
||||
// Only enable module on STM32 platform w/ HAL SPI module enabled
|
||||
#include <sta/config.hpp>
|
||||
#ifdef STA_PLATFORM_STM32
|
||||
# include <sta/stm32/hal.hpp>
|
||||
# ifndef HAL_GPIO_MODULE_ENABLED
|
||||
# error "STM32 GPIO module required!"
|
||||
# endif // !HAL_GPIO_MODULE_ENABLED
|
||||
# ifdef HAL_SPI_MODULE_ENABLED
|
||||
# define STA_STM32_SPI_ENABLED
|
||||
# endif // HAL_SPI_MODULE_ENABLED
|
||||
#endif // STA_PLATFORM_STM32
|
||||
|
||||
|
||||
#if defined(STA_STM32_SPI_ENABLED) || defined(DOXYGEN)
|
||||
|
||||
#include <sta/spi/device.hpp>
|
||||
#include <sta/spi/spi.hpp>
|
||||
|
||||
#include <sta/stm32/clocks.hpp>
|
||||
#include <sta/stm32/gpio_pin.hpp>
|
||||
|
||||
|
||||
/**
|
||||
* @defgroup sta_core_stm32_spi SPI
|
||||
* @ingroup sta_core_stm32
|
||||
* @brief STM32 %SPI module.
|
||||
*/
|
||||
|
||||
|
||||
namespace sta
|
||||
{
|
||||
/**
|
||||
* @addtogroup sta_core_stm32_spi
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/**
|
||||
* @brief STM32 HAL implementation of the `SPI` interface class.
|
||||
*/
|
||||
class STM32SPI : public SPI
|
||||
{
|
||||
public:
|
||||
struct Info
|
||||
{
|
||||
SPI_HandleTypeDef * handle; /**< STM32 HAL handle */
|
||||
uint32_t pclkFreq; /**< Peripheral clock frequency used by interface */
|
||||
};
|
||||
|
||||
public:
|
||||
/**
|
||||
* @param handle STM32 HAL handle
|
||||
* @param pclkFreq Peripheral clock frequency used by %SPI interface
|
||||
* @param mutex Mutex object for managing access. Pass nullptr for no access control
|
||||
*/
|
||||
STM32SPI(SPI_HandleTypeDef * handle, uint32_t pclkFreq, Mutex * mutex = nullptr);
|
||||
|
||||
/**
|
||||
* @param info Interface info
|
||||
* @param mutex Mutex object for managing access. Pass nullptr for no access control
|
||||
*/
|
||||
STM32SPI(const Info & info, Mutex * mutex = nullptr);
|
||||
|
||||
void transfer(uint8_t value) override;
|
||||
void transfer16(uint16_t value) override;
|
||||
void transfer(const uint8_t * buffer, size_t size) override;
|
||||
void transfer(const uint8_t * txBuffer, uint8_t * rxBuffer, size_t size) override;
|
||||
void receive(uint8_t * buffer, size_t size) override;
|
||||
|
||||
void fill(uint8_t value, size_t count) override;
|
||||
|
||||
private:
|
||||
SPI_HandleTypeDef * handle_; /**< STM32 HAL handle */
|
||||
};
|
||||
|
||||
|
||||
/**
|
||||
* @brief STM32 HAL implementation of the `SPIDevice` class.
|
||||
*/
|
||||
class STM32SPIDevice : public SPIDevice
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* @param intf %SPI interface
|
||||
* @param csPin Device CS pin
|
||||
*/
|
||||
STM32SPIDevice(STM32SPI * intf, STM32GpioPin csPin);
|
||||
|
||||
private:
|
||||
STM32GpioPin csPin_; /**< Device CS pin */
|
||||
};
|
||||
|
||||
|
||||
/** @} */
|
||||
} // namespace sta
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get bus info for STM32 %SPI interface via HAL handle.
|
||||
*
|
||||
* Requires STA_STM32_<handle>_PCLK_IDX to be defined for the MCU.
|
||||
* MCU mappings are found in the sta/stm32/mcu/.hpp files.
|
||||
*
|
||||
* Check the MCUs Reference Manual RCC register documentation to see which
|
||||
* peripheral clock is used.
|
||||
*
|
||||
* @param handle STM32 HAL %SPI handle
|
||||
*
|
||||
* @ingroup sta_core_stm32_spi
|
||||
*/
|
||||
#define STA_STM32_SPI_INFO(handle) sta::STM32SPI::Info{&handle, STA_STM32_GET_HANDLE_PCLK_FREQ_FN(handle)()}
|
||||
|
||||
/**
|
||||
* @brief Get bus info for STM32 %SPI interface via index.
|
||||
*
|
||||
* Requires STA_STM32_SPI_<n>_PCLK_IDX to be defined for the MCU.
|
||||
* MCU mappings are found in the sta/stm32/mcu/.hpp files.
|
||||
*
|
||||
* Check the MCUs Reference Manual RCC register documentation to see which
|
||||
* peripheral clock is used.
|
||||
*
|
||||
* @param n STM32 %SPI interface index
|
||||
*
|
||||
* @ingroup sta_core_stm32_spi
|
||||
*/
|
||||
#define STA_STM32_SPI_INFO_N(n) sta::STM32SPI::Info{&handle, STA_STM32_GET_SPI_PCLK_FREQ_FN(n)()}
|
||||
|
||||
|
||||
#endif // STA_STM32_SPI_ENABLED
|
||||
|
||||
#endif // STA_CORE_STM32_SPI_HPP
|
56
include/sta/devices/stm32/uart.hpp
Normal file
56
include/sta/devices/stm32/uart.hpp
Normal file
@@ -0,0 +1,56 @@
|
||||
/**
|
||||
* @file
|
||||
* @brief Implementation of UART using STM32 HAL.
|
||||
*/
|
||||
#ifndef STA_CORE_STM32_UART_HPP
|
||||
#define STA_CORE_STM32_UART_HPP
|
||||
|
||||
|
||||
// Only enable module on STM32 platform w/ HAL UART module enabled
|
||||
#include <sta/config.hpp>
|
||||
#ifdef STA_PLATFORM_STM32
|
||||
# include <sta/stm32/hal.hpp>
|
||||
# ifdef HAL_UART_MODULE_ENABLED
|
||||
# define STA_STM32_UART_ENABLED
|
||||
# endif // HAL_UART_MODULE_ENABLED
|
||||
#endif // STA_PLATFORM_STM32
|
||||
|
||||
|
||||
#if defined(STA_STM32_UART_ENABLED) || defined(DOXYGEN)
|
||||
|
||||
#include <sta/uart.hpp>
|
||||
|
||||
|
||||
/**
|
||||
* @defgroup sta_core_stm32_uart UART
|
||||
* @ingroup sta_core_stm32
|
||||
* @brief STM32 UART module.
|
||||
*/
|
||||
|
||||
|
||||
namespace sta
|
||||
{
|
||||
/**
|
||||
* @brief Implementation of UART interface using HAL.
|
||||
*
|
||||
* @ingroup sta_core_stm32_uart
|
||||
*/
|
||||
class STM32UART : public UART
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* @param handle STM32 HAL handle
|
||||
*/
|
||||
STM32UART(UART_HandleTypeDef * handle);
|
||||
|
||||
void write(const uint8_t * buffer, size_t size) override;
|
||||
|
||||
private:
|
||||
UART_HandleTypeDef * handle_; /**< STM32 HAL handle */
|
||||
};
|
||||
} // namespace sta
|
||||
|
||||
|
||||
#endif // STA_STM32_UART_ENABLED
|
||||
|
||||
#endif // STA_CORE_STM32_UART_HPP
|
43
include/sta/devices/template/delay.hpp
Normal file
43
include/sta/devices/template/delay.hpp
Normal file
@@ -0,0 +1,43 @@
|
||||
/**
|
||||
* @file delay.hpp
|
||||
* @author <your name> (<you>@<your_domain>.com)
|
||||
* @brief
|
||||
* @version 0.1
|
||||
* @date 2023-06-13
|
||||
*
|
||||
* @copyright Copyright (c) 2023
|
||||
*
|
||||
* How to modify this file:
|
||||
* - Ctrl + F and replace "YOUR_DEVICE" with the appropriate name.
|
||||
*/
|
||||
#ifndef STA_CORE_YOUR_DEVICE_DELAY_HPP
|
||||
#define STA_CORE_YOUR_DEVICE_DELAY_HPP
|
||||
|
||||
// Only enable module on YOUR_DEVICE platform
|
||||
#include <sta/config.hpp>
|
||||
|
||||
|
||||
#if defined(STA_PLATFORM_YOUR_DEVICE) || defined(DOXYGEN)
|
||||
|
||||
#include <cstdint>
|
||||
|
||||
namespace sta
|
||||
{
|
||||
/**
|
||||
* @brief Millisecond delay.
|
||||
*
|
||||
* @param ms Milliseconds
|
||||
*/
|
||||
void delayMs(uint32_t ms);
|
||||
|
||||
/**
|
||||
* @brief Microsecond delay.
|
||||
*
|
||||
* @param us Microseconds
|
||||
*/
|
||||
void delayUs(uint32_t us);
|
||||
} // namespace sta
|
||||
|
||||
#endif // STA_PLATFORM_YOUR_DEVICE
|
||||
|
||||
#endif // STA_CORE_YOUR_DEVICE_DELAY_HPP
|
Reference in New Issue
Block a user