added nrf54l15 as target

This commit is contained in:
2025-12-18 11:42:29 +01:00
parent d02d2f24e1
commit 2cfd32abaf
13 changed files with 122 additions and 40 deletions

View File

@@ -5,7 +5,7 @@ target_include_directories(app PRIVATE ./)
add_subdirectory(./led_controller)
add_subdirectory(./stepper_controller)
add_subdirectory(./microros)
add_subdirectory(./usb)
#add_subdirectory(./usb)
target_sources(app PRIVATE
main.cpp

View File

@@ -9,6 +9,7 @@ bool verify_are_devices_available(void) {
devices_ready = false;
}
/*
if (!device_is_ready(led1.port)) {
printk("LED1 not ready\n");
devices_ready = false;
@@ -18,9 +19,10 @@ bool verify_are_devices_available(void) {
printk("LED2 not ready\n");
devices_ready = false;
}
*/
if (!device_is_ready(counter5)) {
printk("Counter 5 not ready\n");
if (!device_is_ready(pid_counter)) {
printk("Counter not ready\n");
devices_ready = false;
}

View File

@@ -13,11 +13,11 @@
#endif
static const struct gpio_dt_spec led0 = GPIO_DT_SPEC_GET(DT_ALIAS(led0), gpios);
static const struct gpio_dt_spec led1 = GPIO_DT_SPEC_GET(DT_ALIAS(led1), gpios);
static const struct gpio_dt_spec led2 = GPIO_DT_SPEC_GET(DT_ALIAS(led2), gpios);
//static const struct gpio_dt_spec led1 = GPIO_DT_SPEC_GET(DT_ALIAS(led1), gpios);
//static const struct gpio_dt_spec led2 = GPIO_DT_SPEC_GET(DT_ALIAS(led2), gpios);
static const struct device *rotenc0 = DEVICE_DT_GET(DT_ALIAS(rotenc0));
static const struct device *stepper0 = DEVICE_DT_GET(DT_ALIAS(stepper0));
static const struct device *counter5 = DEVICE_DT_GET(DT_NODELABEL(counter5));
static const struct device *pid_counter = DEVICE_DT_GET(DT_CHOSEN(pid_counter));
bool verify_are_devices_available(void);

View File

@@ -11,15 +11,17 @@
std_msgs__msg__Bool led_msg;
rcl_node_t LedController::node;
rcl_subscription_t LedController::led0_subscription;
/*
rcl_subscription_t LedController::led1_subscription;
rcl_subscription_t LedController::led2_subscription;
*/
void led0_callback(const void *msg){
gpio_pin_configure_dt(&led0, ((std_msgs__msg__Bool *)msg)->data ? GPIO_OUTPUT_ACTIVE : GPIO_OUTPUT_INACTIVE);
}
/*
void led1_callback(const void *msg){
gpio_pin_configure_dt(&led1, ((std_msgs__msg__Bool *)msg)->data ? GPIO_OUTPUT_ACTIVE : GPIO_OUTPUT_INACTIVE);
}
@@ -28,7 +30,7 @@ void led1_callback(const void *msg){
void led2_callback(const void *msg){
gpio_pin_configure_dt(&led2, ((std_msgs__msg__Bool *)msg)->data ? GPIO_OUTPUT_ACTIVE : GPIO_OUTPUT_INACTIVE);
}
*/
rcl_ret_t LedController::setup(rclc_support_t* support, rclc_executor_t* executor) {
@@ -44,6 +46,7 @@ rcl_ret_t LedController::setup(rclc_support_t* support, rclc_executor_t* executo
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Bool),
"/nucleo/led0"));
/*
RCL_RETURN_ON_ERROR(rclc_subscription_init_default(
&LedController::led1_subscription,
&LedController::node,
@@ -55,6 +58,7 @@ rcl_ret_t LedController::setup(rclc_support_t* support, rclc_executor_t* executo
&LedController::node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Bool),
"/nucleo/led2"));
*/
RCL_RETURN_ON_ERROR(rclc_executor_add_subscription(
executor,
@@ -64,6 +68,7 @@ rcl_ret_t LedController::setup(rclc_support_t* support, rclc_executor_t* executo
ON_NEW_DATA
));
/*
RCL_RETURN_ON_ERROR(rclc_executor_add_subscription(
executor,
&LedController::led1_subscription,
@@ -79,6 +84,7 @@ rcl_ret_t LedController::setup(rclc_support_t* support, rclc_executor_t* executo
led2_callback,
ON_NEW_DATA
));
*/
return RCL_RET_OK;
}
@@ -86,7 +92,7 @@ rcl_ret_t LedController::setup(rclc_support_t* support, rclc_executor_t* executo
void LedController::kill() {
rcl_subscription_fini(&LedController::led0_subscription, &LedController::node);
rcl_subscription_fini(&LedController::led1_subscription, &LedController::node);
rcl_subscription_fini(&LedController::led2_subscription, &LedController::node);
//rcl_subscription_fini(&LedController::led1_subscription, &LedController::node);
//rcl_subscription_fini(&LedController::led2_subscription, &LedController::node);
rcl_node_fini(&LedController::node);
}

View File

@@ -12,6 +12,8 @@ public:
private:
static rcl_node_t node;
static rcl_subscription_t led0_subscription;
/*
static rcl_subscription_t led1_subscription;
static rcl_subscription_t led2_subscription;
*/
};

View File

@@ -10,7 +10,7 @@
#include <rmw_microros/rmw_microros.h>
#include "devices.hpp"
#include "usb_cdc_acm.hpp"
//#include "usb_cdc_acm.hpp"
#include "stepper_controller.hpp"
#include "microros_state_machine.hpp"
@@ -23,7 +23,7 @@ int main(void)
StepperController::init();
usb_init();
//usb_init();
rmw_uros_set_custom_transport(
MICRO_ROS_FRAMING_REQUIRED,

View File

@@ -89,12 +89,12 @@ void StepperController::init() {
alarm_cfg = {
.callback = counter_cb,
.ticks = counter_us_to_ticks(counter5, PID_LOOP_US), // 2 ms = 500 Hz
.ticks = counter_us_to_ticks(pid_counter, PID_LOOP_US), // 2 ms = 500 Hz
.flags = 0,
};
counter_set_channel_alarm(counter5, 0, &alarm_cfg);
counter_start(counter5);
counter_set_channel_alarm(pid_counter, 0, &alarm_cfg);
counter_start(pid_counter);
sample_angle();
last_angle = current_angle;