diff --git a/README.md b/README.md
index 3f1588ae20..5d70f5276b 100644
--- a/README.md
+++ b/README.md
@@ -607,72 +607,73 @@ you specific needs.
DS1631 |
DS18B20 |
EA-DOG |
+ENCODER-INPUT |
ENCODER-INPUT-BITBANG |
-ENCODER-OUTPUT-BITBANG |
+ENCODER-OUTPUT-BITBANG |
FT245 |
FT6X06 |
GPIO-SAMPLER |
HCLAx |
HD44780 |
-HMC58x |
+HMC58x |
HMC6343 |
HX711 |
I2C-EEPROM |
ILI9341 |
IS31FL3733 |
-ITG3200 |
+ITG3200 |
L3GD20 |
LAN8720A |
LAWICEL |
LIS302DL |
LIS3DSH |
-LIS3MDL |
+LIS3MDL |
LM75 |
LP503X |
LSM303A |
LSM6DS33 |
LTC2984 |
-MAX6966 |
+MAX6966 |
MAX7219 |
MCP23X17 |
MCP2515 |
MMC5603 |
NOKIA5110 |
-NRF24 |
+NRF24 |
TFT-DISPLAY |
PAT9125EL |
PCA8574 |
PCA9535 |
PCA9548A |
-PCA9685 |
+PCA9685 |
SH1106 |
SIEMENS-S65 |
SIEMENS-S75 |
SK6812 |
SK9822 |
-SSD1306 |
+SSD1306 |
ST7586S |
STTS22H |
STUSB4500 |
SX1276 |
TCS3414 |
-TCS3472 |
+TCS3472 |
TLC594X |
TMP102 |
TMP12X |
TMP175 |
TOUCH2046 |
-VL53L0 |
+VL53L0 |
VL6180 |
WS2812 |
diff --git a/examples/arduino_nano/encoder_input/main.cpp b/examples/arduino_nano/encoder_input_bitbang/main.cpp
similarity index 84%
rename from examples/arduino_nano/encoder_input/main.cpp
rename to examples/arduino_nano/encoder_input_bitbang/main.cpp
index 65bb5e1e8a..e49ff11c64 100644
--- a/examples/arduino_nano/encoder_input/main.cpp
+++ b/examples/arduino_nano/encoder_input_bitbang/main.cpp
@@ -10,15 +10,14 @@
// ----------------------------------------------------------------------------
#include
-#include
-#include
#include
+#include
+#include
using namespace modm::platform;
// Connect the encoders outputs to D7 and D8 Pins (usually the outer pins)
// The common third pin (usually in the middle) is connected to GND.
-// Don't add any resistors or filters. It's all in the MCU and the driver.
modm::BitBangEncoderInput encoder;
MODM_ISR(TIMER2_COMPA)
@@ -48,22 +47,19 @@ main()
Board::initialize();
LedD13::setOutput();
- encoder.connect();
-
+ encoder.initialize();
init_Timer2();
enableInterrupts();
int value(0);
modm::ShortPeriodicTimer heartbeat(500ms);
- modm::ShortPeriodicTimer outputValue(1000ms);
while (true)
{
- if (heartbeat.execute()) Board::LedD13::toggle();
- if (outputValue.execute())
- {
- value += encoder.getIncrement();
+ if (heartbeat.execute()) {
+ Board::LedD13::toggle();
+ value += encoder.getDelta();
MODM_LOG_INFO << "value: " << value << modm::endl;
}
}
diff --git a/examples/arduino_nano/encoder_input/project.xml b/examples/arduino_nano/encoder_input_bitbang/project.xml
similarity index 89%
rename from examples/arduino_nano/encoder_input/project.xml
rename to examples/arduino_nano/encoder_input_bitbang/project.xml
index 703c79eff9..6a15971d34 100644
--- a/examples/arduino_nano/encoder_input/project.xml
+++ b/examples/arduino_nano/encoder_input_bitbang/project.xml
@@ -1,7 +1,7 @@
modm:arduino-nano
-
+
modm:build:scons
diff --git a/examples/blue_pill_f103/encoder_input/main.cpp b/examples/blue_pill_f103/encoder_input/main.cpp
new file mode 100644
index 0000000000..51a1f7cc1c
--- /dev/null
+++ b/examples/blue_pill_f103/encoder_input/main.cpp
@@ -0,0 +1,74 @@
+/*
+ * Copyright (c) 2021, Thomas Sommer
+ *
+ * This file is part of the modm project.
+ *
+ * This Source Code Form is subject to the terms of the Mozilla Public
+ * License, v. 2.0. If a copy of the MPL was not distributed with this
+ * file, You can obtain one at http://mozilla.org/MPL/2.0/.
+ */
+// ----------------------------------------------------------------------------
+
+#include
+#include
+#include
+#include
+
+// ----------------------------------------------------------------------------
+// Set the log level
+#undef MODM_LOG_LEVEL
+#define MODM_LOG_LEVEL modm::log::INFO
+
+// Create an IODeviceWrapper around the Uart Peripheral we want to use
+modm::IODeviceWrapper< Usart2, modm::IOBuffer::BlockIfFull > loggerDevice;
+
+// Set all four logger streams to use the UART
+modm::log::Logger modm::log::debug(loggerDevice);
+modm::log::Logger modm::log::info(loggerDevice);
+modm::log::Logger modm::log::warning(loggerDevice);
+modm::log::Logger modm::log::error(loggerDevice);
+
+int
+main()
+{
+ Board::initialize();
+
+ Usart2::connect();
+ Usart2::initialize();
+
+ // Each Timer can drive one Encoder
+ // For Timer2 and Timer3 you have 2 Gpio options
+ // When using one of PB3 or PB4 you also have to disable JTAG debugging during shared pins
+
+ // Timer1:
+ modm::EncoderInput encoder;
+
+ // Timer2:
+ // modm::EncoderInput encoder;
+ // modm::EncoderInput encoder;
+ // AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_JTAGDISABLE;
+
+ // Timer3:
+ // modm::EncoderInput encoder;
+ // modm::EncoderInput encoder;
+ // Disable JTAG to make PB3, PB4 available as Gpio
+ // AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_JTAGDISABLE;
+
+ // Timer4:
+ // modm::EncoderInput encoder;
+
+ encoder.initialize(true);
+
+ modm::ShortPeriodicTimer heartbeat(500ms);
+
+ while (true)
+ {
+ if(heartbeat.execute()) {
+ Board::LedGreen::toggle();
+ MODM_LOG_INFO << "Encoder Delta: " << encoder.getDelta() << modm::endl;
+ MODM_LOG_INFO << "Encoder Absolut: " << encoder.getValue() << modm::endl;
+ }
+ }
+
+ return 0;
+}
diff --git a/examples/blue_pill_f103/encoder_input/openocd.cfg b/examples/blue_pill_f103/encoder_input/openocd.cfg
new file mode 100644
index 0000000000..b157e7e432
--- /dev/null
+++ b/examples/blue_pill_f103/encoder_input/openocd.cfg
@@ -0,0 +1,2 @@
+# Replace this with your custom programmer
+source [find interface/stlink-v2.cfg]
diff --git a/examples/blue_pill_f103/encoder_input/project.xml b/examples/blue_pill_f103/encoder_input/project.xml
new file mode 100644
index 0000000000..34707ffb99
--- /dev/null
+++ b/examples/blue_pill_f103/encoder_input/project.xml
@@ -0,0 +1,18 @@
+
+ modm:blue-pill-f103
+
+
+
+
+
+ modm:debug
+ modm:platform:uart:2
+ modm:processing:timer
+ modm:driver:encoder_input
+ modm:platform:timer:1
+ modm:platform:timer:2
+ modm:platform:timer:3
+ modm:platform:timer:4
+ modm:build:scons
+
+
diff --git a/examples/blue_pill_f103/encoder_input_bitbang/main.cpp b/examples/blue_pill_f103/encoder_input_bitbang/main.cpp
new file mode 100644
index 0000000000..5b32144e22
--- /dev/null
+++ b/examples/blue_pill_f103/encoder_input_bitbang/main.cpp
@@ -0,0 +1,82 @@
+/*
+ * Copyright (c) 2021, Thomas Sommer
+ *
+ * This file is part of the modm project.
+ *
+ * This Source Code Form is subject to the terms of the Mozilla Public
+ * License, v. 2.0. If a copy of the MPL was not distributed with this
+ * file, You can obtain one at http://mozilla.org/MPL/2.0/.
+ */
+// ----------------------------------------------------------------------------
+
+#include
+#include
+#include
+#include
+
+// ----------------------------------------------------------------------------
+// Set the log level
+#undef MODM_LOG_LEVEL
+#define MODM_LOG_LEVEL modm::log::INFO
+
+// Create an IODeviceWrapper around the Uart Peripheral we want to use
+modm::IODeviceWrapper< Usart2, modm::IOBuffer::BlockIfFull > loggerDevice;
+
+// Set all four logger streams to use the UART
+modm::log::Logger modm::log::debug(loggerDevice);
+modm::log::Logger modm::log::info(loggerDevice);
+modm::log::Logger modm::log::warning(loggerDevice);
+modm::log::Logger modm::log::error(loggerDevice);
+
+// Connect the encoders outputs to D7 and D8 Pins (usually the outer pins)
+// The common third pin (usually in the middle) is connected to GND.
+modm::BitBangEncoderInput encoder;
+
+MODM_ISR(TIM2)
+{
+ Timer2::acknowledgeInterruptFlags(Timer2::InterruptFlag::Update);
+ encoder.update();
+}
+
+void
+init_Timer2(const uint16_t period)
+{
+ Timer2::enable();
+ Timer2::setMode(Timer2::Mode::UpCounter);
+
+ Timer2::template setPeriod(period);
+ Timer2::enableInterruptVector(true, 10);
+ Timer2::enableInterrupt(Timer2::Interrupt::Update);
+
+ Timer2::applyAndReset();
+ Timer2::start();
+}
+
+int
+main()
+{
+ Board::initialize();
+
+ Usart2::connect();
+ Usart2::initialize();
+
+ encoder.initialize();
+ init_Timer2(1000); // 1ms period
+
+ int value(0);
+
+ modm::ShortPeriodicTimer heartbeat(1s);
+
+ while (true)
+ {
+ if (heartbeat.execute()) {
+ Board::LedGreen::toggle();
+
+ const auto delta = encoder.getDelta();
+ MODM_LOG_INFO << "Delta: " << delta << modm::endl;
+
+ value += delta;
+ MODM_LOG_INFO << "Encoder Absolut: " << value << modm::endl;
+ }
+ }
+}
diff --git a/examples/blue_pill_f103/encoder_input_bitbang/openocd.cfg b/examples/blue_pill_f103/encoder_input_bitbang/openocd.cfg
new file mode 100644
index 0000000000..b157e7e432
--- /dev/null
+++ b/examples/blue_pill_f103/encoder_input_bitbang/openocd.cfg
@@ -0,0 +1,2 @@
+# Replace this with your custom programmer
+source [find interface/stlink-v2.cfg]
diff --git a/examples/blue_pill_f103/encoder_input_bitbang/project.xml b/examples/blue_pill_f103/encoder_input_bitbang/project.xml
new file mode 100644
index 0000000000..717a9f9d8d
--- /dev/null
+++ b/examples/blue_pill_f103/encoder_input_bitbang/project.xml
@@ -0,0 +1,15 @@
+
+ modm:blue-pill-f103
+
+
+
+
+
+ modm:debug
+ modm:platform:uart:2
+ modm:processing:timer
+ modm:driver:encoder_input.bitbang
+ modm:platform:timer:2
+ modm:build:scons
+
+
diff --git a/src/modm/driver/encoder/bitbang_encoder_input.hpp b/src/modm/driver/encoder/bitbang_encoder_input.hpp
index b826112f37..9fc732f3f5 100644
--- a/src/modm/driver/encoder/bitbang_encoder_input.hpp
+++ b/src/modm/driver/encoder/bitbang_encoder_input.hpp
@@ -26,18 +26,19 @@ namespace modm
*
* @tparam SignalA First modm::platform::Gpio pin to input the encoder signal.
* @tparam SignalB Second modm::platform::Gpio pin to input the encoder signal.
- * @tparam POSTSCALER n_cycles to count as one in-/decrement.
- * @tparam DeltaType Must be signed integer and fit at least POSTSCALER. The Bigger
+ * @tparam PRESCALER n_cycles to count as one in-/decrement.
+ * @tparam DeltaType Must be signed integral and fit at least PRESCALER. The Bigger
* DeltaType, the more inc-/decrements can be stored temporarily.
+ * @tparam ValueType Must be unsigned integral.
*/
-template
class BitBangEncoderInput
{
- static_assert(std::popcount(POSTSCALER) == 1,
- "POSTSCALER must be an integer to basis 2 and not 0: 1, 2, 4, 8, 16, ...");
- static_assert(POSTSCALER <= std::numeric_limits::max(),
- "DeltaType is to small for POSTSCALER.");
+ static_assert(std::popcount(PRESCALER) == 1,
+ "PRESCALER must be an integer to basis 2 and not 0: 1, 2, 4, 8, 16, ...");
+ static_assert(PRESCALER <= std::numeric_limits::max(),
+ "DeltaType is to small for PRESCALER.");
using Signals = modm::platform::SoftwareGpioPort;
@@ -47,19 +48,19 @@ class BitBangEncoderInput
uint8_t inline getRaw();
public:
- using ValueType = DeltaType;
BitBangEncoderInput() : raw_last(0), delta(0){};
+ using InputType = modm::platform::Gpio::InputType;
// Connect SingalA and SignalB and store power-up state
inline void
- connect();
+ initialize(const modm::platform::Gpio::InputType inputType = modm::platform::Gpio::InputType::PullUp);
// Call @1kHz for manual movement
inline void
update();
- ValueType
- getIncrement();
+ DeltaType
+ getDelta();
private:
uint8_t raw_last;
diff --git a/src/modm/driver/encoder/bitbang_encoder_input.lb b/src/modm/driver/encoder/bitbang_encoder_input.lb
index 7a56588606..7d5084f84f 100644
--- a/src/modm/driver/encoder/bitbang_encoder_input.lb
+++ b/src/modm/driver/encoder/bitbang_encoder_input.lb
@@ -15,7 +15,7 @@ def init(module):
module.description = """
# Quadrature Encoder Input
-This driver decodes a AB (incremental) encoder signal.
+This driver decodes an AB (incremental) encoder signal.
Ported from code created by Peter Dannegger:
https://www.mikrocontroller.net/articles/Drehgeber.
"""
diff --git a/src/modm/driver/encoder/bitbang_encoder_input_impl.hpp b/src/modm/driver/encoder/bitbang_encoder_input_impl.hpp
index c18c844f4f..c87a882a16 100644
--- a/src/modm/driver/encoder/bitbang_encoder_input_impl.hpp
+++ b/src/modm/driver/encoder/bitbang_encoder_input_impl.hpp
@@ -15,10 +15,9 @@
#include
-template
+template
inline uint8_t
-modm::BitBangEncoderInput::getRaw()
+modm::BitBangEncoderInput::getRaw()
{
const uint8_t read = Signals::read();
// convert graycode to binary
@@ -28,25 +27,26 @@ modm::BitBangEncoderInput::getRaw()
return raw;
}
-template
+template
inline void
-modm::BitBangEncoderInput::connect()
+modm::BitBangEncoderInput::initialize(
+ const modm::platform::Gpio::InputType inputType
+)
{
- Signals::setInput(::Gpio::InputType::PullUp);
+ Signals::setInput(inputType);
// Tare power-on state
modm::delay(10us);
raw_last = getRaw();
}
-template
+template
inline void
-modm::BitBangEncoderInput::update()
+modm::BitBangEncoderInput::update()
{
- uint8_t raw = getRaw();
+ const uint8_t raw = getRaw();
const uint8_t diff = raw_last - raw;
+
if (diff & 0b01)
{
raw_last = raw;
@@ -54,16 +54,13 @@ modm::BitBangEncoderInput::update()
}
}
-template
+template
DeltaType
-modm::BitBangEncoderInput::getIncrement()
+modm::BitBangEncoderInput::getDelta()
{
::modm::atomic::Lock _;
- DeltaType val = delta;
-
- delta &= (POSTSCALER - 1); // mask out higher bits
- constexpr uint8_t shift = std::log2(POSTSCALER); // Number of fraction bits
- return val >> shift; // return whats left without fractions
+ DeltaType ret = delta;
+ delta &= (PRESCALER - 1); // Only keep prescaler fraction
+ return ret >> int(std::log2(PRESCALER)); // return delta without prescaler fraction
}
diff --git a/src/modm/driver/encoder/encoder_input.hpp b/src/modm/driver/encoder/encoder_input.hpp
new file mode 100644
index 0000000000..0aee94766a
--- /dev/null
+++ b/src/modm/driver/encoder/encoder_input.hpp
@@ -0,0 +1,76 @@
+/*
+ * Copyright (c) 2021, Thomas Sommer
+ *
+ * This file is part of the modm project.
+ *
+ * This Source Code Form is subject to the terms of the Mozilla Public
+ * License, v. 2.0. If a copy of the MPL was not distributed with this
+ * file, You can obtain one at http://mozilla.org/MPL/2.0/.
+ */
+
+#pragma once
+
+#include
+
+namespace modm
+{
+/**
+ * @brief Gray code decoder using STM32 Timer mode
+ *
+ * @tparam Timer STM32 General purpose timer
+ * @tparam SignalA First modm::platform::Gpio pin that connects to Timer::Ch1
+ * @tparam SignalB Second modm::platform::Gpio pin that connects to Timer::Ch2
+ * @tparam PRESCALER How many encoder pulses to count as one
+ * @tparam DeltaType Fast encoders may require int16_t
+ */
+template
+class EncoderInput
+{
+public:
+ void
+ initialize(
+ const uint8_t filter = 4,
+ const modm::platform::Gpio::InputType inputType = modm::platform::Gpio::InputType::PullUp
+ ) {
+ SignalA::setInput(inputType);
+ SignalB::setInput(inputType);
+
+ Timer::template connect();
+
+ Timer::enable();
+
+ Timer::setMode(Timer::Mode::UpCounter, Timer::SlaveMode::Encoder3);
+ Timer::setPrescaler(PRESCALER);
+
+ if(filter) {
+ Timer::configureInputChannel(1, filter);
+ Timer::configureInputChannel(2, filter);
+ }
+
+ Timer::applyAndReset();
+ Timer::start();
+ last = Timer::getValue();
+ }
+
+ uint16_t
+ getValue()
+ {
+ return Timer::getValue();
+ }
+
+ DeltaType
+ getDelta()
+ {
+ uint16_t current = Timer::getValue();
+ const DeltaType delta = current - last;
+ last = current;
+
+ return delta;
+ }
+
+
+private:
+ uint16_t last = 0;
+};
+} // namespace modm
\ No newline at end of file
diff --git a/src/modm/driver/encoder/encoder_input.lb b/src/modm/driver/encoder/encoder_input.lb
new file mode 100644
index 0000000000..f865377553
--- /dev/null
+++ b/src/modm/driver/encoder/encoder_input.lb
@@ -0,0 +1,28 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+#
+# Copyright (c) 2021, Thomas Sommer
+#
+# This file is part of the modm project.
+#
+# This Source Code Form is subject to the terms of the Mozilla Public
+# License, v. 2.0. If a copy of the MPL was not distributed with this
+# file, You can obtain one at http://mozilla.org/MPL/2.0/.
+# -----------------------------------------------------------------------------
+
+def init(module):
+ module.name = ":driver:encoder_input"
+ module.description = """
+# Quadrature Encoder Input using STM32 general purpose Timer
+
+This driver decodes an AB (incremental) encoder signal.
+"""
+
+def prepare(module, options):
+ module.depends(":architecture:atomic")
+ return options[":target"].identifier.platform =="stm32"
+
+
+def build(env):
+ env.outbasepath = "modm/src/modm/driver/encoder"
+ env.copy("encoder_input.hpp")
diff --git a/src/modm/platform/timer/stm32/advanced.cpp.in b/src/modm/platform/timer/stm32/advanced.cpp.in
index dc63a0e8ce..135ea3e5ac 100644
--- a/src/modm/platform/timer/stm32/advanced.cpp.in
+++ b/src/modm/platform/timer/stm32/advanced.cpp.in
@@ -66,6 +66,35 @@ modm::platform::Timer{{ id }}::setMode(Mode mode, SlaveMode slaveMode,
}
// ----------------------------------------------------------------------------
+void
+modm::platform::Timer{{ id }}::configureInputChannel(uint32_t channel, uint8_t filter) {
+ channel -= 1; // 1..4 -> 0..3
+
+ // disable channel
+ TIM{{ id }}->CCER &= ~(TIM_CCER_CC1E << (channel * 4));
+
+ uint32_t flags = static_cast(filter&0xf) << 4;
+
+ if (channel <= 1)
+ {
+ const uint32_t offset = 8 * channel;
+
+ flags <<= offset;
+ flags |= TIM{{ id }}->CCMR1 & ~(0xf0 << offset);
+
+ TIM{{ id }}->CCMR1 = flags;
+ }
+ else {
+ const uint32_t offset = 8 * (channel - 2);
+
+ flags <<= offset;
+ flags |= TIM{{ id }}->CCMR2 & ~(0xf0 << offset);
+
+ TIM{{ id }}->CCMR2 = flags;
+ }
+ TIM{{ id }}->CCER |= TIM_CCER_CC1E << (channel * 4);
+}
+
void
modm::platform::Timer{{ id }}::configureInputChannel(uint32_t channel,
InputCaptureMapping input, InputCapturePrescaler prescaler,
diff --git a/src/modm/platform/timer/stm32/advanced.hpp.in b/src/modm/platform/timer/stm32/advanced.hpp.in
index fb810d486b..94da70daca 100644
--- a/src/modm/platform/timer/stm32/advanced.hpp.in
+++ b/src/modm/platform/timer/stm32/advanced.hpp.in
@@ -303,6 +303,9 @@ public:
}
public:
+ static void
+ configureInputChannel(uint32_t channel, uint8_t filter);
+
static void
configureInputChannel(uint32_t channel, InputCaptureMapping input,
InputCapturePrescaler prescaler,
diff --git a/src/modm/platform/timer/stm32/general_purpose.cpp.in b/src/modm/platform/timer/stm32/general_purpose.cpp.in
index 73de44c306..d05d6e7ecb 100644
--- a/src/modm/platform/timer/stm32/general_purpose.cpp.in
+++ b/src/modm/platform/timer/stm32/general_purpose.cpp.in
@@ -81,6 +81,35 @@ modm::platform::Timer{{ id }}::setMode(Mode mode, SlaveMode slaveMode,
}
// ----------------------------------------------------------------------------
+void
+modm::platform::Timer{{ id }}::configureInputChannel(uint32_t channel, uint8_t filter) {
+ channel -= 1; // 1..4 -> 0..3
+
+ // disable channel
+ TIM{{ id }}->CCER &= ~(TIM_CCER_CC1E << (channel * 4));
+
+ uint32_t flags = static_cast(filter&0xf) << 4;
+
+ if (channel <= 1)
+ {
+ const uint32_t offset = 8 * channel;
+
+ flags <<= offset;
+ flags |= TIM{{ id }}->CCMR1 & ~(0xf0 << offset);
+
+ TIM{{ id }}->CCMR1 = flags;
+ }
+ else {
+ const uint32_t offset = 8 * (channel - 2);
+
+ flags <<= offset;
+ flags |= TIM{{ id }}->CCMR2 & ~(0xf0 << offset);
+
+ TIM{{ id }}->CCMR2 = flags;
+ }
+ TIM{{ id }}->CCER |= TIM_CCER_CC1E << (channel * 4);
+}
+
void
modm::platform::Timer{{ id }}::configureInputChannel(uint32_t channel,
InputCaptureMapping input, InputCapturePrescaler prescaler,
diff --git a/src/modm/platform/timer/stm32/general_purpose.hpp.in b/src/modm/platform/timer/stm32/general_purpose.hpp.in
index 74848e1a70..45209e8e50 100644
--- a/src/modm/platform/timer/stm32/general_purpose.hpp.in
+++ b/src/modm/platform/timer/stm32/general_purpose.hpp.in
@@ -317,6 +317,9 @@ public:
public:
+ static void
+ configureInputChannel(uint32_t channel, uint8_t filter);
+
static void
configureInputChannel(uint32_t channel, InputCaptureMapping input,
InputCapturePrescaler prescaler,
diff --git a/src/modm/platform/timer/stm32/general_purpose_base.hpp.in b/src/modm/platform/timer/stm32/general_purpose_base.hpp.in
index 7b9b84f249..7a2b1e6d6d 100644
--- a/src/modm/platform/timer/stm32/general_purpose_base.hpp.in
+++ b/src/modm/platform/timer/stm32/general_purpose_base.hpp.in
@@ -234,7 +234,7 @@ public:
/**
* TODO Description
*/
- void
+ static void
configureInputChannel(uint32_t channel, InputCaptureMapping input,
InputCapturePrescaler prescaler, InputCapturePolarity polarity, uint8_t filter);
@@ -256,7 +256,7 @@ public:
* @param channel [1..4]
* @param value Compare value
*/
- static inline void
+ static void
setCompareValue(uint32_t channel, uint16_t value);
/**
@@ -265,7 +265,7 @@ public:
* @param channel [1..4]
* @return Current compare value
*/
- static inline uint16_t
+ static uint16_t
getCompareValue(uint32_t channel);
};