Skip to content

Commit

Permalink
Merge branch 'main' into echavemann/capsense-driver
Browse files Browse the repository at this point in the history
  • Loading branch information
echavemann authored Dec 7, 2024
2 parents 4c5cb2e + f11fc00 commit f353bce
Show file tree
Hide file tree
Showing 33 changed files with 577 additions and 90 deletions.
2 changes: 2 additions & 0 deletions .clang-format-ignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
src/scheduler/scheduler.cpp
include/scheduler/scheduler.hpp
9 changes: 3 additions & 6 deletions Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ ETL_INCLUDES += ./external/etl/include/etl/string_stream.h
ETL_INCLUDES += ./external/etl/include/etl/to_string.h
ETL_INCLUDES += ./external/etl/include/etl/delegate.h
ETL_INCLUDES += ./external/etl/include/etl/unordered_map.h
ETL_INCLUDES += ./external/etl/include/etl/set.h

# Source and header files
APP_HEADER_PATHS += ./include
Expand Down Expand Up @@ -49,12 +50,8 @@ CPP_FILES := $(wildcard src/*.cpp include/*.hpp)

.PHONY: format
format:
clang-format -style=file -i $(CPP_FILES)

.PHONY: tidy
tidy:
clang-tidy $(CPP_FILES) -- -std=c++20
find src include -name '*.cpp' -o -name '*.hpp' | xargs clang-format --style=file -i

.PHONY: lint
lint: format tidy
lint: format

Original file line number Diff line number Diff line change
Expand Up @@ -161,9 +161,9 @@ typedef struct
*/
#define NRF_DRV_TWI_DEFAULT_CONFIG \
{ \
.frequency = (nrf_drv_twi_frequency_t)TWI_DEFAULT_CONFIG_FREQUENCY, \
.scl = 31, \
.sda = 31, \
.frequency = (nrf_drv_twi_frequency_t)TWI_DEFAULT_CONFIG_FREQUENCY, \
.interrupt_priority = TWI_DEFAULT_CONFIG_IRQ_PRIORITY, \
.clear_bus_init = TWI_DEFAULT_CONFIG_CLR_BUS_INIT, \
.hold_bus_uninit = TWI_DEFAULT_CONFIG_HOLD_BUS_UNINIT, \
Expand Down
8 changes: 4 additions & 4 deletions include/drivers/button_driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include "drivers/gpio_pin.hpp"
#include "drivers/gpio_pin_event.hpp"
#include "microbit_v2.h"
#include "scheduler/user_callback_storage.hpp"

namespace edge::drivers {
class ButtonController {
Expand All @@ -17,9 +18,8 @@ class ButtonController {
GPIOPinEvent event_a;
GPIOPinEvent event_b;

using SubscriptionArray = etl::array<ProcessCallbackPtr, MAX_PROCESSES>;
SubscriptionArray a_subscriptions;
SubscriptionArray b_subscriptions;
UserCallbackStorage a_subscriptions;
UserCallbackStorage b_subscriptions;

ButtonController();
~ButtonController() = default;
Expand All @@ -35,7 +35,7 @@ class ButtonController {
bool get_button_pressed(ButtonType button_type);

void subscribe_button_press(
ButtonType type, ProcessCallbackPtr callback, uint8_t process_id
ButtonType type, ProcessCallbackPtr callback, ProcessId process_id
);
};
} // namespace edge::drivers
4 changes: 2 additions & 2 deletions include/drivers/driver_commands.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,9 +11,9 @@ void do_async_work();

etl::optional<int> handle_command(DriverCommand type, int arg1, int arg2, int arg3);

void handle_subscribe(
etl::optional<int> handle_subscribe(
DriverSubscribe type, ProcessCallbackPtr callback, int arg1, int arg2,
uint8_t process_id
ProcessId process_id
);

} // namespace edge::drivers
5 changes: 3 additions & 2 deletions include/drivers/driver_enums.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,11 @@ enum class DriverCommand {
LED_DISPLAY = 1,
BUTTONS = 2,
TERMINAL_OUTPUT = 3,
CAPTOUCH = 4,
TIMER_CANCEL = 4,
CAPTOUCH = 5,
};

enum class DriverSubscribe { NOTIFY_BUTTON_PRESS = 0 };
enum class DriverSubscribe { NOTIFY_BUTTON_PRESS = 0, TIMER_START = 1 };

enum class GPIOConfiguration { OUT, IN_NORES, IN_PDR, IN_PUR };

Expand Down
69 changes: 69 additions & 0 deletions include/drivers/virtual_timer_controller.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
#pragma once

#include "nrf_timer.h"
#include "stdint.h"
#include "util.hpp"

namespace edge::drivers {
extern "C" {
void TIMER3_IRQHandler(void);
}

struct timer {
uint32_t id;

ProcessCallbackPtr callback;

uint32_t timer_value;
ProcessId process_id;
uint32_t duration;
bool periodic;
};

inline bool operator<(const timer& first, const timer& second)
{
return first.timer_value < second.timer_value;
}

// Reserves Timer 3
class VirtualTimerController {
static constexpr nrf_timer_frequency_t TIMER_FREQUENCY = NRF_TIMER_FREQ_16MHz;
inline static NRF_TIMER_Type* const TIMER = NRF_TIMER3;
static constexpr size_t MAX_TIMERS = 512;
etl::set<timer, MAX_TIMERS> timers_;
uint32_t virtual_timer_start(const timer& timer);

public:
uint32_t virtual_timer_start(
uint32_t microseconds, ProcessCallbackPtr callback, ProcessId timer_creator,
bool periodic
);
void virtual_timer_cancel(uint32_t timer_id);

static VirtualTimerController& get();

VirtualTimerController(VirtualTimerController&) = delete;
VirtualTimerController(VirtualTimerController&&) = delete;
VirtualTimerController& operator=(VirtualTimerController&) = delete;
VirtualTimerController& operator=(VirtualTimerController&&) = delete;

friend void TIMER3_IRQHandler(void);

private:
void trigger_ready_timers();

etl::optional<timer> get_ready_timer();

void enqueue_next_timer() const;

uint32_t read_timer() const;

uint32_t timer_start(
uint32_t microseconds, ProcessCallbackPtr callback, ProcessId timer_creator
);

VirtualTimerController();
~VirtualTimerController() = default;
};

} // namespace edge::drivers
5 changes: 3 additions & 2 deletions include/faults/fault_handler.hpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#pragma once

#include "config.hpp"
#include "scheduler/user_callback_storage.hpp"
#include "util.hpp"

namespace edge {
Expand All @@ -9,7 +10,7 @@ class FaultHandler {
FaultHandler();
~FaultHandler();

etl::array<etl::optional<ProcessCallbackPtr>, MAX_PROCESSES> error_callbacks;
UserCallbackStorage error_callbacks;

public:
FaultHandler(const FaultHandler&) = delete;
Expand All @@ -22,6 +23,6 @@ class FaultHandler {
// To be called by raw handlers in raw_fault_handling.cpp
void fault_triggered(FaultType fault_type, uint32_t* stack_ptr);

void set_fault_callback(uint8_t process_id, ProcessCallbackPtr callback_ptr);
void set_fault_callback(ProcessId process_id, ProcessCallbackPtr callback_ptr);
};
} // namespace edge
16 changes: 9 additions & 7 deletions include/hal/gpio_event_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,15 +6,16 @@ namespace edge::aidan {

extern "C" void GPIOTE_IRQHandler();

static constexpr uint8_t GPIO_PINS = 32;
static constexpr uint8_t MAX_GPIO_CALLBACKS = 32;

// TODO: Add a controller for other GPIOTE events (channels)?
class GPIOEventController {
public:
enum class Port { ZERO, ONE };
using GPIOEventCallback = etl::delegate<void(nrf_gpio_pin_sense_t, int)>;

private:
etl::array<etl::optional<GPIOEventCallback>, GPIO_PINS> callbacks{etl::nullopt};
etl::unordered_map<int, GPIOEventCallback, MAX_GPIO_CALLBACKS> callbacks{};

void handle_gpiote_port_event() const;
GPIOEventController();
Expand All @@ -24,14 +25,15 @@ class GPIOEventController {

static GPIOEventController& get();

// GPIOEventController& operator=(const GPIOEventController&) = delete;
// GPIOEventController& operator=(GPIOEventController&&) = delete;
// GPIOEventController(const GPIOEventController&) = delete;
// GPIOEventController(GPIOEventController&&) = delete;
GPIOEventController& operator=(const GPIOEventController&) = delete;
GPIOEventController& operator=(GPIOEventController&&) = delete;
GPIOEventController(const GPIOEventController&) = delete;
GPIOEventController(GPIOEventController&&) = delete;

// TODO/idea, what if we instead made this a factory?
void set_gpio_callback(
uint32_t pin, PinPullMode pin_resistance, GPIOEventCallback callback
uint32_t pin, PinPullMode pin_resistance, GPIOEventCallback callback,
PinSense sense = PinSense::HIGH
);

void clear_gpio_callback(uint32_t pin);
Expand Down
3 changes: 3 additions & 0 deletions include/hal/hal_enums.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,9 @@ enum class PinPullMode {
NONE = NRF_GPIO_PIN_NOPULL
};

enum class PinSense { HIGH, LOW };

nrf_gpio_pin_pull_t to_nrf_gpio_pin_pull(PinPullMode mode);
nrf_gpio_pin_sense_t to_nrf_gpio_pin_sense(PinSense sense);

} // namespace edge::aidan
14 changes: 14 additions & 0 deletions include/hal/i2c_controller.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
#pragma once

namespace edge::aidan {

class I2CController {
public:
~I2CController() = default;
static I2CController& get();

private:
I2CController();
};

} // namespace edge::aidan
91 changes: 91 additions & 0 deletions include/hal/i2c_wrapper.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,91 @@
#pragma once

#include "nrf_delay.h"
#include "nrf_twi_mngr.h"

#include <stdint.h>

namespace edge::aidan {

static const uint8_t LSM303AGR_ACC_ADDRESS = 0x19;
static const uint8_t LSM303AGR_MAG_ADDRESS = 0x1E;

typedef struct {
float x_axis;
float y_axis;
float z_axis;
} lsm303agr_measurement_t;

// Accel Enums
typedef enum {
STATUS_REG_AUX_A = 0x07,
OUT_TEMP_L_A = 0x0C,
OUT_TEMP_H_A = 0x0D,
INT_COUNTER_REG_A = 0x0E,
WHO_AM_I_A = 0x0F,
TEMP_CFG_REG_A = 0x1F,
CTRL_REG1_A = 0x20,
CTRL_REG2_A = 0x21,
CTRL_REG3_A = 0x22,
CTRL_REG4_A = 0x23,
CTRL_REG5_A = 0x24,
CTRL_REG6_A = 0x25,
REFERENCE_DATACAPTURE_A = 0x26,
STATUS_REG_A = 0x27,
OUT_X_L_A = 0x28,
OUT_X_H_A = 0x29,
OUT_Y_L_A = 0x2A,
OUT_Y_H_A = 0x2B,
OUT_Z_L_A = 0x2C,
OUT_Z_H_A = 0x2D,
FIFO_CTRL_REG_A = 0x2E,
FIFO_SRC_REG_A = 0x2F,
INT1_CFG_A = 0x30,
INT1_SRC_A = 0x31,
INT1_THS_A = 0x32,
INT1_DURATION_A = 0x33,
INT2_CFG_A = 0x34,
INT2_SRC_A = 0x35,
INT2_THS_A = 0x36,
INT2_DURATION_A = 0x37,
CLICK_CFG_A = 0x38,
CLICK_SRC_A = 0x39,
CLICK_THS_A = 0x3A,
TIME_LIMIT_A = 0x3B,
TIME_LATENCY_A = 0x3C,
TIME_WINDOW_A = 0x3D,
ACT_THS_A = 0x3E,
ACT_DUR_A = 0x3F,
} lsm303agr_acc_reg_t;

// Magneto Enums
typedef enum {
OFFSET_X_REG_L_M = 0x45,
OFFSET_X_REG_H_M = 0x46,
OFFSET_Y_REG_L_M = 0x47,
OFFSET_Y_REG_H_M = 0x48,
OFFSET_Z_REG_L_M = 0x49,
OFFSET_Z_REG_H_M = 0x4A,
WHO_AM_I_M = 0x4F,
CFG_REG_A_M = 0x60,
CFG_REG_B_M = 0x61,
CFG_REG_C_M = 0x62,
INT_CTRL_REG_M = 0x63,
INT_SOURCE_REG_M = 0x64,
INT_THS_L_REG_M = 0x65,
INT_THS_H_REG_M = 0x66,
STATUS_REG_M = 0x67,
OUTX_L_REG_M = 0x68,
OUTX_H_REG_M = 0x69,
OUTY_L_REG_M = 0x6A,
OUTY_H_REG_M = 0x6B,
OUTZ_L_REG_M = 0x6C,
OUTZ_H_REG_M = 0x6D,
} lsm303agr_mag_reg_t;

uint8_t i2c_reg_read(uint8_t i2c_addr, uint8_t reg_addr);

void i2c_reg_write(uint8_t i2c_addr, uint8_t reg_addr, uint8_t data);

void lsm303agr_init(const nrf_twi_mngr_t* i2c);
} // namespace edge::aidan
6 changes: 4 additions & 2 deletions include/ipc/ipc_manager.hpp
Original file line number Diff line number Diff line change
@@ -1,12 +1,13 @@
#pragma once

#include "config.hpp"
#include "scheduler/user_callback_storage.hpp"
#include "util.hpp"

namespace edge {
class IPCManager {
etl::unordered_map<ProcessName, uint8_t, MAX_PROCESSES> name_to_id;
etl::array<ProcessCallbackPtr, MAX_PROCESSES> ipc_communicators{nullptr};
UserCallbackStorage ipc_communicators{};

IPCManager() = default;
~IPCManager() = default;
Expand All @@ -19,7 +20,8 @@ class IPCManager {
static IPCManager& get();

void register_callback(
uint8_t process_id, const ProcessName& process_name, ProcessCallbackPtr callback
ProcessId process_id, const ProcessName& process_name,
ProcessCallbackPtr callback
);
void send_message(const ProcessName& destination_name, int value);
};
Expand Down
2 changes: 1 addition & 1 deletion include/scheduler/mpu.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

namespace edge {
class MpuController {
MpuController() { }
MpuController() {}

~MpuController() { disable_mpu(); };

Expand Down
4 changes: 2 additions & 2 deletions include/scheduler/pending_process_callbacks.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,10 +28,10 @@ class PendingProcessCallbacks {
PendingProcessCallbacks& operator=(PendingProcessCallbacks&&) = delete;

void add_ready_callback(
uint8_t process_id, ProcessCallbackPtr callback, int arg1 = 0, int arg2 = 0
ProcessId process_id, ProcessCallbackPtr callback, int arg1 = 0, int arg2 = 0
);

etl::optional<drivers::subscribe_callback> get_ready_callback(uint8_t process_id);
etl::optional<drivers::subscribe_callback> get_ready_callback(ProcessId process_id);

static PendingProcessCallbacks& get();
};
Expand Down
Loading

0 comments on commit f353bce

Please sign in to comment.