feat(project): Restructure software for multi-app setup

- Reorganize the software directory to support multiple Zephyr applications (gateway, slave_node).

- Create a clear separation between applications and shared libraries.

- Add placeholder files for gateway and slave_node applications.
This commit is contained in:
Eduard Iten 2025-07-01 08:20:25 +02:00
parent 423e3947ab
commit fbeaa916b9
25 changed files with 53 additions and 1588 deletions

View File

@ -1,14 +1,8 @@
# SPDX-License-Identifier: Apache-2.0 # Top-level CMakeLists.txt for the irrigation system project
cmake_minimum_required(VERSION 3.20.0) cmake_minimum_required(VERSION 3.20)
# This line should ideally be after project() and find_package(Zephyr) # Add the subdirectories for the applications and libraries
# target_include_directories(app PRIVATE ${ZEPHYR_BASE}/include/zephyr/drivers) # <-- WRONG POSITION add_subdirectory(apps/gateway)
add_subdirectory(apps/slave_node)
list(APPEND BOARD_ROOT ${CMAKE_CURRENT_SOURCE_DIR}) add_subdirectory(lib)
find_package(Zephyr REQUIRED HINTS $ENV{ZEPHYR_BASE})
project(valve_node)
target_include_directories(app PRIVATE ${ZEPHYR_BASE}/include/zephyr/drivers)
target_sources(app PRIVATE src/main2.c)

View File

@ -1,25 +0,0 @@
# SPDX-License-Identifier: Apache-2.0
cmake_minimum_required(VERSION 3.20.0)
list(APPEND BOARD_ROOT ${CMAKE_CURRENT_SOURCE_DIR})
find_package(Zephyr REQUIRED HINTS $ENV{ZEPHYR_BASE})
project(valve_node)
target_sources(app PRIVATE src/main.c)
target_sources(app PRIVATE lib/canbus.c)
# source files for modbus waterlevel sensor
zephyr_library_sources_ifdef(CONFIG_HAS_MODBUS_WATERLEVEL_SENSOR
lib/waterlevel_sensor.c
)
#source files for valve
zephyr_library_sources_ifdef(CONFIG_HAS_VALVE
lib/valve.c
)
zephyr_include_directories(
lib
)

View File

@ -0,0 +1,6 @@
cmake_minimum_required(VERSION 3.20)
find_package(Zephyr REQUIRED HINTS $ENV{ZEPHYR_BASE})
project(gateway)
target_sources(app PRIVATE src/main.c)

View File

@ -0,0 +1,3 @@
# Zephyr configuration for the Gateway
CONFIG_NETWORKING=y
CONFIG_NET_TCP=y

View File

@ -0,0 +1,13 @@
/*
* Copyright (c) 2025 Eduard Iten
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <zephyr/kernel.h>
int main(void)
{
printk("Hello from Gateway!\n");
return 0;
}

View File

@ -0,0 +1,6 @@
cmake_minimum_required(VERSION 3.20)
find_package(Zephyr REQUIRED HINTS $ENV{ZEPHYR_BASE})
project(slave_node)
target_sources(app PRIVATE src/main.c)

View File

@ -0,0 +1,2 @@
# Zephyr configuration for the Slave Node
CONFIG_GPIO=y

View File

@ -0,0 +1,13 @@
/*
* Copyright (c) 2025 Eduard Iten
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <zephyr/kernel.h>
int main(void)
{
printk("Hello from Slave Node!\n");
return 0;
}

View File

@ -1,58 +0,0 @@
config BOARD_VALVE_NODE
select SOC_STM32F103XB
mainmenu "APP CAN Settings"
config LOOPBACK_MODE
bool "Loopback LOOPBACK_MODE"
default n
help
Set the can controller to loopback mode.
This allows testing without a second board.
mainmenu "APP Logging Settings"
config LOG_CAN_LEVEL
int "Log level for CAN"
default 3
range 0 7
help
Set the log level for CAN messages.
0 = None, 1 = Error, 2 = Warning, 3 = Info, 4 = Debug, 5 = Trace, 6 = Debug2, 7 = Debug3
config LOG_SETTINGS_LEVEL
int "Log level for settings"
default 3
range 0 7
help
Set the log level for CAN messages.
0 = None, 1 = Error, 2 = Warning, 3 = Info, 4 = Debug, 5 = Trace, 6 = Debug2, 7 = Debug3
config LOG_WATERLEVELSENSOR_LEVEL
int "Log level for waterlevel sensor"
default 3
range 0 7
help
Set the log level for CAN messages.
0 = None, 1 = Error, 2 = Warning, 3 = Info, 4 = Debug, 5 = Trace, 6 = Debug2, 7 = Debug3
config LOG_VALVE_LEVEL
int "Log level for valve control"
default 3
range 0 7
help
Set the log level for valve control messages.
0 = None, 1 = Error, 2 = Warning, 3 = Info, 4 = Debug, 5 = Trace, 6 = Debug2, 7 = Debug3
mainmenu "Irrigation controller node configuration"
config HAS_MODBUS_WATERLEVEL_SENSOR
bool "Has modbus water level sensor"
default n
help
Enable modbus water level sensor support.
This allows reading the water level from a modbus device.
config HAS_VALVE
bool "Has valve control"
default n
help
Enable valve control support.
This allows controlling valves via CAN messages.

View File

@ -1,11 +0,0 @@
# SPDX-License-Identifier: Apache-2.0
# keep first
board_runner_args(stm32cubeprogrammer "--port=swd" "--reset-mode=hw")
board_runner_args(jlink "--device=STM32F103RB" "--speed=4000")
# keep first
include(${ZEPHYR_BASE}/boards/common/stm32cubeprogrammer.board.cmake)
include(${ZEPHYR_BASE}/boards/common/openocd-stm32.board.cmake)
include(${ZEPHYR_BASE}/boards/common/jlink.board.cmake)
include(${ZEPHYR_BASE}/boards/common/blackmagicprobe.board.cmake)

View File

@ -1,10 +0,0 @@
board:
name: valve_node
full_name: Irrigation system CANbus valve node
socs:
- name: stm32f103xb
# revision:
# format: number
# default: "1"
# revisions:
# -name: "1"

View File

@ -1,206 +0,0 @@
/*
* Copyright (c) 2017 Linaro Limited
*
* SPDX-License-Identifier: Apache-2.0
*/
/dts-v1/;
#include <st/f1/stm32f1.dtsi>
#include <st/f1/stm32f103Xb.dtsi>
#include <st/f1/stm32f103r(8-b)tx-pinctrl.dtsi>
#include <zephyr/dt-bindings/input/input-event-codes.h>
/ {
model = "Iten engineering Valve Node";
compatible = "st,stm32f103rb";
can_loopback0: can_loopback0 {
status = "disabled";
compatible = "zephyr,can-loopback";
};
chosen {
zephyr,console = &usart1;
zephyr,shell-uart = &usart1;
zephyr,sram = &sram0;
zephyr,flash = &flash0;
zephyr,canbus = &can1;
};
leds: leds {
compatible = "gpio-leds";
green_led_2: led_2 {
gpios = <&gpiob 2 GPIO_ACTIVE_HIGH>;
label = "User LD2";
};
};
gpio_keys {
compatible = "gpio-keys";
user_button: button {
label = "User";
gpios = <&gpioc 13 GPIO_ACTIVE_LOW>;
zephyr,code = <INPUT_KEY_0>;
};
endstopopen: endstop_open {
gpios = <&gpiob 4 (GPIO_ACTIVE_LOW | GPIO_PULL_UP)>;
label = "Endstop Open";
};
endstopclose: endstop_closed {
gpios = <&gpiob 5 (GPIO_ACTIVE_LOW | GPIO_PULL_UP)>;
label = "Endstop Close";
};
statusopen: status_open {
gpios = <&gpiob 14 (GPIO_ACTIVE_LOW | GPIO_PULL_UP)>;
label = "Status Open";
};
statusclose: status_close {
gpios = <&gpioa 8 (GPIO_ACTIVE_LOW | GPIO_PULL_UP)>;
label = "Status Close";
};
};
aliases {
led0 = &green_led_2;
sw0 = &user_button;
watchdog0 = &iwdg;
die-temp0 = &die_temp;
adc-motor-current = &motor_current_channel;
adc-vref = &vref_channel;
};
};
&clk_lsi {
status = "okay";
};
&clk_hse {
clock-frequency = <DT_FREQ_M(8)>;
status = "okay";
};
&pll {
mul = <9>;
clocks = <&clk_hse>;
status = "okay";
};
&rcc {
clocks = <&pll>;
clock-frequency = <DT_FREQ_M(72)>;
ahb-prescaler = <1>;
apb1-prescaler = <2>;
apb2-prescaler = <1>;
adc-prescaler = <6>;
};
&usart1 {
pinctrl-0 = <&usart1_tx_pa9 &usart1_rx_pa10>;
pinctrl-names = "default";
status = "okay";
current-speed = <115200>;
};
&usart2 {
pinctrl-0 = <&usart2_tx_pa2 &usart2_rx_pa3>;
current-speed = <9600>;
pinctrl-names = "default";
status = "okay";
modbus0 {
compatible = "zephyr,modbus-serial";
status = "okay";
};
};
&usart3 {
pinctrl-0 = <&usart3_tx_pb10 &usart3_rx_pb11>;
current-speed = <115200>;
pinctrl-names = "default";
};
&i2c1 {
pinctrl-0 = <&i2c1_scl_remap1_pb8 &i2c1_sda_remap1_pb9>;
pinctrl-names = "default";
status = "okay";
clock-frequency = <I2C_BITRATE_FAST>;
};
&iwdg {
status = "okay";
};
&rtc {
clocks = <&rcc STM32_CLOCK_BUS_APB1 0x10000000>,
<&rcc STM32_SRC_LSI RTC_SEL(2)>;
status = "okay";
};
&adc1 {
pinctrl-0 = <&adc_pb1_pins>;
pinctrl-names = "default";
status = "okay";
#address-cells = <1>;
#size-cells = <0>;
motor_current_channel: channel@9 {
reg = <0x9>;
zephyr,gain = "ADC_GAIN_1";
zephyr,reference = "ADC_REF_VDD_1";
zephyr,acquisition-time = <49159>;
zephyr,resolution = <12>;
};
vref_channel: channel@11 { /* 17 dezimal = 11 hex */
reg = <0x11>;
zephyr,gain = "ADC_GAIN_1";
zephyr,reference = "ADC_REF_VDD_1";
zephyr,acquisition-time = <49159>;
zephyr,resolution = <12>;
};
};
&die_temp {
status = "okay";
};
&dma1 {
status = "okay";
};
&flash0 {
partitions {
compatible = "fixed-partitions";
#address-cells = <1>;
#size-cells = <1>;
storage_partition: partition@1f800 {
label = "storage";
reg = <0x0001f800 DT_SIZE_K(2)>;
};
};
};
&can1 {
pinctrl-0 = <&can_rx_pa11 &can_tx_pa12>;
pinctrl-names = "default";
status= "okay";
bitrate = <125000>;
};
&exti {
status = "okay";
};
&pinctrl {
adc_pb1_pins: adc_pb1_pins {
pinmux = <STM32F1_PINMUX('B', 1, ANALOG, NO_REMAP)>;
};
};

View File

@ -1,31 +0,0 @@
# SPDX-License-Identifier: Apache-2.0
# enable uart driver
CONFIG_SERIAL=y
# enable console
CONFIG_CONSOLE=y
# enable GPIO
CONFIG_GPIO=y
# modbus config
CONFIG_UART_INTERRUPT_DRIVEN=y
CONFIG_UART_LINE_CTRL=n
CONFIG_MODBUS=y
CONFIG_MODBUS_ROLE_CLIENT=y
# can config
CONFIG_CAN=y
CONFIG_CAN_INIT_PRIORITY=80
#CONFIG_CAN_MAX_FILTER=5
CONFIG_CAN_ACCEPT_RTR=y
# settings
CONFIG_FLASH=y
CONFIG_FLASH_MAP=y
CONFIG_SETTINGS=y
CONFIG_SETTINGS_RUNTIME=y
CONFIG_NVS=y
CONFIG_SETTINGS_NVS=y
CONFIG_HEAP_MEM_POOL_SIZE=256
CONFIG_MPU_ALLOW_FLASH_WRITE=y

View File

@ -0,0 +1,4 @@
# Add your shared libraries here
# Example:
# add_library(modbus modbus/modbus.c)
# target_include_directories(modbus PUBLIC .)

View File

@ -1,286 +0,0 @@
#include "canbus.h"
#include <zephyr/logging/log.h>
#include <zephyr/kernel.h>
#include <zephyr/sys/byteorder.h>
#include <zephyr/drivers/can.h>
#include <stdlib.h>
#ifdef CONFIG_HAS_MODBUS_WATERLEVEL_SENSOR
#include "waterlevel_sensor.h"
#endif // CONFIG_HAS_MODBUS_WATERLEVEL_SENSOR
#ifdef CONFIG_HAS_VALVE
#include "valve.h"
#endif // CONFIG_HAS_VALVE
const struct device *const can_dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_canbus));
LOG_MODULE_REGISTER(canbus, CONFIG_LOG_CAN_LEVEL);
K_MSGQ_DEFINE(canbus_msgq, sizeof(struct can_frame), CANBUS_RX_MSGQ_SIZE, 4);
K_THREAD_STACK_DEFINE(canbus_rx_stack, CANBUS_RX_THREAD_STACK_SIZE);
uint8_t node_id = 0; // Default node ID, can be set later
uint8_t can_msg_id = 0;
k_tid_t canbus_rx_thread_id;
struct k_thread canbus_rx_thread_data;
int canbus_rx_filter_id = -1;
void canbus_rx_callback(const struct device *dev, struct can_frame *frame, void *user_data)
{
int rc;
ARG_UNUSED(dev);
ARG_UNUSED(user_data);
if (frame->id >> 8 != node_id) // Check if the frame ID matches the node ID
{
LOG_DBG("Received CAN frame with ID %d, but it does not match node ID %d", frame->id >> 8, node_id);
return; // Ignore frames that do not match the node ID
}
// Process the received CAN frame
rc = k_msgq_put(&canbus_msgq, frame, K_NO_WAIT);
if (rc != 0)
{
LOG_ERR("Failed to put CAN frame into message queue: %d", rc);
}
}
void canbus_thread(void *arg1, void *arg2, void *arg3)
{
ARG_UNUSED(arg1);
ARG_UNUSED(arg2);
ARG_UNUSED(arg3);
LOG_INF("CAN bus thread started");
// Main loop for CAN bus operations
while (1)
{
int rc;
struct can_frame frame;
k_msgq_get(&canbus_msgq, &frame, K_FOREVER); // Wait for a message from the queue
LOG_DBG("Received CAN frame with ID: 0x%02x, DLC: %d, RTR: %d",
frame.id, frame.dlc, (uint8_t)(frame.flags & CAN_FRAME_RTR));
LOG_HEXDUMP_DBG(frame.data, frame.dlc, "CAN frame data");
uint8_t reg = frame.id & 0xFF; // Extract register from the frame ID
bool is_rtr = (frame.flags & CAN_FRAME_RTR) != 0; // Check if it's a remote transmission request
switch (reg)
{
#ifdef CONFIG_HAS_MODBUS_WATERLEVEL_SENSOR
case CANBUS_REG_WATERLEVEL_LEVEL:
case CANBUS_REG_WATERLEVEL_ZERO_POINT:
case CANBUS_REG_WATERLEVEL_MAX_POINT:
waterlevel_command_t command;
command.cmd = is_rtr ? WATERLEVEL_CMD_GET : WATERLEVEL_CMD_SET; // Determine command type based on RTR
command.reg = reg; // Set the register ID
int16_t value = 0; // Initialize value to 0
if (!is_rtr) // If it's not a remote request, extract the value from the frame data
{
if (frame.dlc < sizeof(command.data))
{ LOG_ERR("Received frame with insufficient data length: %d", frame.dlc);
continue; // Skip processing if data length is insufficient
}
value = sys_be16_to_cpu(*(uint16_t *)frame.data); // Convert data from big-endian to host byte order
command.data = value; // Set the data field
LOG_DBG("Setting command data to: %d", value);
}
extern struct k_msgq waterlevel_sensor_msgq; // Declare the water level sensor message queue
k_msgq_put(&waterlevel_sensor_msgq, &command, K_NO_WAIT);
break;
#endif // CONFIG_HAS_MODBUS_WATERLEVEL_SENSOR
#ifdef CONFIG_HAS_VALVE
case CANBUS_REG_VALVE_STATUS:
case CANBUS_REG_VALVE_OPERATION:
if (is_rtr)
{
LOG_DBG("Received remote request for valve status or operation");
if (reg == CANBUS_REG_VALVE_STATUS)
{
valve_send_status(); // Send the current valve status
}
else if (reg == CANBUS_REG_VALVE_OPERATION)
{
valve_send_operation(); // Send the current valve operation state
} else {
LOG_ERR("Unknown valve register: 0x%02x", reg);
continue; // Skip processing if the register is unknown
}
}
else
{
LOG_ERR("Received CAN frame with data for valve status or operation, but RTR is not set");
continue; // Skip processing if RTR is not set for valve status or operation
}
break;
case CANBUS_REG_VALVE_COMMAND:
{
if (is_rtr) {
LOG_ERR("Received remote request for valve command, but this is not supported");
continue; // Skip processing if RTR is set for valve command
} else {
// Extract the command from the frame data
if (frame.dlc < sizeof(uint8_t)) {
LOG_ERR("Received frame with insufficient data length for valve command: %d", frame.dlc);
continue; // Skip processing if data length is insufficient
}
uint8_t command = frame.data[0]; // Get the command from the first byte of data
LOG_DBG("Received valve command: 0x%02x", command);
rc = valve_cmd(command); // Send the command to the valve
if (rc < 0) {
LOG_ERR("Failed to send valve command: %d", rc);
continue; // Skip processing if sending the command failed
}
}
break;
}
default:
LOG_DBG("Received CAN frame with unknown register: 0x%02x", reg);
break;
}
#endif // CONFIG_HAS_VALVE
}
}
int canbus_init(void)
{
int rc = 0;
if (!device_is_ready(can_dev))
{
LOG_ERR("CAN device %s is not ready", can_dev->name);
return -ENODEV;
}
#ifdef CONFIG_LOOPBACK_MODE
rc = can_set_mode(can_dev, CAN_MODE_LOOPBACK);
if (rc != 0)
{
LOG_ERR("Failed to set CAN loopback mode: %d", rc);
return rc;
}
#endif
rc = can_start(can_dev);
if (rc != 0)
{
printf("Error starting CAN controller [%d]", rc);
return 0;
}
LOG_DBG("CAN device %s is ready", can_dev->name);
// Initialize the CAN RX thread
canbus_rx_thread_id = k_thread_create(&canbus_rx_thread_data, canbus_rx_stack,
K_THREAD_STACK_SIZEOF(canbus_rx_stack), canbus_thread,
NULL, NULL, NULL,
CANBUS_RX_THREAD_PRIORITY, 0, K_NO_WAIT);
k_thread_name_set(canbus_rx_thread_id, "canbus_rx");
const struct can_filter filter = {
.id = node_id << 8, // Standard ID with node ID in the first byte
.mask = 0x700, // Mask to match the first byte of the ID
.flags = 0, // No special flags
};
canbus_rx_filter_id = can_add_rx_filter(can_dev, canbus_rx_callback, NULL, &filter);
LOG_DBG("CAN RX filter added for node ID %d", canbus_rx_filter_id);
return 0;
}
void canbus_tx8_callback(const struct device *dev, int error, void *user_data)
{
ARG_UNUSED(dev);
uint8_t frame_id = *(uint8_t *)user_data; // Retrieve the frame ID from user data
if (error != 0)
{
LOG_ERR("CAN transmission error. Error code: %d, Frame ID: %d", error, frame_id);
}
else
{
LOG_DBG("CAN message with Frame ID %d sent successfully", frame_id);
}
free(user_data); // Free the allocated memory for frame ID
}
int canbus_send8(uint16_t reg, uint8_t value)
{
int rc = 0;
struct can_frame frame = {
.id = (node_id << 8) | reg, // Standard ID with node ID in the first byte
.dlc = sizeof(value), // Data Length Code (DLC)
};
frame.data[0] = value; // Set the value in the first byte of the data
uint8_t *frame_id = malloc(sizeof(uint8_t)); // Allocate memory for frame ID
LOG_DBG("Preparing to send 8-bit value 0x%02x to register 0x%02x on node %d", value, reg, node_id);
if (frame_id == NULL)
{
LOG_ERR("Failed to allocate memory for frame ID");
return -ENOMEM; // Not enough memory
}
*frame_id = can_msg_id++; // Increment message ID for uniqueness
LOG_DBG("Using frame ID: %d", *frame_id);
rc = can_send(can_dev, &frame, CANBUS_TX_TIMEOUT, canbus_tx8_callback, frame_id);
// Send the CAN frame with a timeout and callback
if (rc != 0)
{
LOG_ERR("Failed to queue CAN frame: %d", rc);
free(frame_id); // Free the allocated memory for frame ID
return rc;
}
return 0;
}
void canbus_tx16_callback(const struct device *dev, int error, void *user_data)
{
ARG_UNUSED(dev);
uint8_t frame_id = *(uint8_t *)user_data; // Retrieve the frame ID from user data
if (error != 0)
{
LOG_ERR("CAN transmission error. Error code: %d, Frame ID: %d", error, frame_id);
}
else
{
LOG_DBG("CAN message with Frame ID %d sent successfully", frame_id);
}
free(user_data); // Free the allocated memory for frame ID
}
int canbus_send16(uint16_t reg, uint16_t value)
{
int rc = 0;
union data_type
{
int16_t value;
uint8_t bytes[2];
} data;
data.value = sys_cpu_to_be16(value); // Convert value to big-endian format
struct can_frame frame = {
.id = (node_id << 8) | reg, // Standard ID with node ID in the first byte
.dlc = sizeof(data), // Data Length Code (DLC)
};
memcpy(frame.data, data.bytes, sizeof(data)); // Copy data into the frame
uint8_t *frame_id = malloc(sizeof(uint8_t)); // Allocate memory for frame ID
LOG_DBG("Preparing to send 16-bit value 0x%04x to register 0x%02x on node %d", value, reg, node_id);
if (frame_id == NULL)
{
LOG_ERR("Failed to allocate memory for frame ID");
return -ENOMEM; // Not enough memory
}
*frame_id = can_msg_id++; // Increment message ID for uniqueness
LOG_DBG("Using frame ID: %d", *frame_id);
rc = can_send(can_dev, &frame, CANBUS_TX_TIMEOUT, canbus_tx16_callback, frame_id);
// Send the CAN frame with a timeout and callback
if (rc != 0)
{
LOG_ERR("Failed to queue CAN frame: %d", rc);
free(frame_id); // Free the allocated memory for frame ID
return rc;
}
LOG_DBG("Queued 16-bit value 0x%04x to register 0x%02x on node %d, frame ID: %d",
value, reg, node_id, *frame_id);
return 0;
}

View File

@ -1,16 +0,0 @@
#ifndef __CANBUS_H__
#define __CANBUS_H__
#include <stdint.h>
#include "canbus_registers.h"
#define CANBUS_RX_THREAD_STACK_SIZE (512) // Stack size for the CAN RX thread
#define CANBUS_RX_THREAD_PRIORITY (5) // Priority for the CAN RX thread
#define CANBUS_RX_MSGQ_SIZE (5) // Size of the message queue for CAN RX thread
#define CANBUS_TX_TIMEOUT K_MSEC(100) // Timeout for sending CAN messages in milliseconds
int canbus_init(void);
int canbus_send8(uint16_t reg, uint8_t value);
int canbus_send16(uint16_t reg, uint16_t value);
#endif // __CANBUS_H__

View File

@ -1,42 +0,0 @@
#ifndef __CANBUS_REGISTERS_H__
#define __CANBUS_REGISTERS_H__
enum canbus_registers {
CANBUS_REG_REBOOT = 0x00,
CANBUS_REG_STATE = 0x01,
CANBUS_REG_ERROR = 0x02,
CANBUS_REG_VALVE_STATUS = 0x10,
CANBUS_REG_VALVE_OPERATION = 0x11,
CANBUS_REG_VALVE_COMMAND = 0x12,
CANBUS_REG_WATERLEVEL_STATE = 0x20,
CANBUS_REG_WATERLEVEL_LEVEL = 0x21,
CANBUS_REG_WATERLEVEL_ZERO_POINT = 0x22,
CANBUS_REG_WATERLEVEL_MAX_POINT = 0x23,
};
enum valve_status {
VALVE_STATE_CLOSED = 0x00,
VALVE_STATE_OPEN = 0x01,
VALVE_STATE_ERROR = 0x02,
VALVE_STATE_UNKNOWN = 0x03,
};
enum valve_operation_state {
VALVE_OPERATION_IDLE = 0x00,
VALVE_OPERATION_OPENING = 0x01,
VALVE_OPERATION_CLOSING = 0x02,
};
enum valve_command {
VALVE_COMMAND_STOP = 0x00,
VALVE_COMMAND_OPEN = 0x01,
VALVE_COMMAND_CLOSE = 0x02,
};
enum waterlevel_state {
WATERLEVEL_STATE_OK = 0x00,
WATERLEVEL_STATE_MODBUS_ERROR = 0x02,
};
#endif // __CANBUS_REGISTERS_H__

View File

@ -1,163 +0,0 @@
#include <zephyr/kernel.h>
#include <zephyr/logging/log.h>
#include "canbus.h"
#include "canbus_registers.h"
#include "valve.h"
LOG_MODULE_REGISTER(valve, CONFIG_LOG_VALVE_LEVEL);
K_THREAD_STACK_DEFINE(valve_thread_stack, VALVE_THREAD_STACK_SIZE);
K_MSGQ_DEFINE(valve_msgq, sizeof(int), VALVE_MSGQ_SIZE, 4);
k_tid_t valve_thread_id;
struct k_thread valve_thread_data;
valve_status_t valve_status_data = {
.valve_state = VALVE_STATE_UNKNOWN,
.valve_operation = VALVE_OPERATION_IDLE,
};
int valve_start_thread(void)
{
int rc;
// Initialize the valve
rc = valve_init();
if (rc < 0)
{
LOG_ERR("Failed to initialize valve: %d", rc);
return rc;
}
// Create the valve thread
valve_thread_id = k_thread_create(&valve_thread_data, valve_thread_stack,
K_THREAD_STACK_SIZEOF(valve_thread_stack),
(k_thread_entry_t)valve_cmd, NULL, NULL, NULL,
VALVE_THREAD_PRIORITY, 0, K_NO_WAIT);
k_thread_name_set(valve_thread_id, "valve");
LOG_INF("Valve thread started successfully");
while (1)
{
// Wait for commands from the message queue
int cmd;
rc = k_msgq_get(&valve_msgq, &cmd, VALVE_STATE_INTERVAL);
if (rc == 0)
{
// Process the command
rc = valve_cmd(cmd);
if (rc < 0)
{
LOG_ERR("Failed to process valve command: %d", rc);
}
}
else
{
valve_send_status(); // Send current valve status periodically
}
}
return 0;
}
int valve_init(void)
{
return 0;
}
int valve_cmd(int cmd)
{
switch (cmd)
{
case VALVE_COMMAND_OPEN:
if (valve_status_data.valve_state != VALVE_STATE_OPEN)
{
valve_status_data.valve_state = VALVE_STATE_OPEN;
valve_status_data.valve_operation = VALVE_OPERATION_OPENING;
valve_send_status(); // Send updated status before opening
valve_send_operation(); // Send updated operation state before opening
k_sleep(VALVE_OPENING_TIME); // Simulate opening time
valve_status_data.valve_operation = VALVE_OPERATION_IDLE; // Set operation to idle after opening
valve_send_status(); // Send updated status after opening
valve_send_operation(); // Send updated operation state after opening
}
break;
case VALVE_COMMAND_CLOSE:
if (valve_status_data.valve_state != VALVE_STATE_CLOSED)
{
valve_status_data.valve_operation = VALVE_OPERATION_CLOSING;
valve_send_operation(); // Send updated operation state before closing
k_sleep(VALVE_CLOSING_TIME); // Simulate closing time
valve_status_data.valve_state = VALVE_STATE_CLOSED; // Set valve state to closed after closing
valve_status_data.valve_operation = VALVE_OPERATION_IDLE; // Set operation to idle after closing
valve_send_status(); // Send updated status after closing
valve_send_operation(); // Send updated operation state after closing
}
break;
case VALVE_COMMAND_STOP:
valve_status_data.valve_operation = VALVE_OPERATION_IDLE;
break;
default:
LOG_ERR("Unknown valve command: %d", cmd);
return -EINVAL; // Invalid command
}
return 0;
}
int valve_send_status(void)
{
int rc = canbus_send8(CANBUS_REG_VALVE_STATUS, valve_status_data.valve_state);
if (rc != 0)
{
LOG_ERR("Failed to send valve status: %d", rc);
return rc;
}
char *state_str;
switch (valve_status_data.valve_state)
{
case VALVE_STATE_CLOSED:
state_str = "CLOSED";
break;
case VALVE_STATE_OPEN:
state_str = "OPEN";
break;
case VALVE_STATE_ERROR:
state_str = "ERROR";
break;
case VALVE_STATE_UNKNOWN:
state_str = "UNKNOWN";
break;
default:
state_str = "INVALID";
break;
}
LOG_INF("Valve status sent: %s", state_str);
return 0;
}
int valve_send_operation(void)
{
int rc = canbus_send8(CANBUS_REG_VALVE_OPERATION, valve_status_data.valve_operation);
if (rc != 0)
{
LOG_ERR("Failed to send valve operation: %d", rc);
return rc;
}
char *operation_str;
switch (valve_status_data.valve_operation)
{
case VALVE_OPERATION_IDLE:
operation_str = "IDLE";
break;
case VALVE_OPERATION_OPENING:
operation_str = "OPENING";
break;
case VALVE_OPERATION_CLOSING:
operation_str = "CLOSING";
break;
default:
operation_str = "UNKNOWN";
break;
}
LOG_INF("Valve operation sent: %s", operation_str);
return 0;
}

View File

@ -1,27 +0,0 @@
#ifndef __VALVE_H__
#define __VALVE_H__
#define VALVE_OPENING_TIME K_MSEC(4500) // Time to open the valve
#define VALVE_CLOSING_TIME K_MSEC(4500) // Time to close the valve
#define VALVE_MAX_OPENING_TIME K_MSEC(5000) // Maximum time to open the valve
#define VALVE_MAX_CLOSING_TIME K_MSEC(5000) // Maximum time to close the valve
#define VALVE_STATE_INTERVAL K_SECONDS(5 * 60) // Interval to check the valve state
#define VALVE_THREAD_STACK_SIZE (512) // Stack size for the valve thread
#define VALVE_THREAD_PRIORITY (2) // Priority for the valve thread
#define VALVE_MSGQ_SIZE (5) // Size of the message queue for valve operations
#include <stdint.h>
#include "canbus_registers.h"
typedef struct {
uint8_t valve_state;
uint8_t valve_operation;
} valve_status_t;
int valve_init(void);
int valve_cmd(int cmd);
int valve_send_status(void);
int valve_send_operation(void);
#endif // __VALVE_H__

View File

@ -1,383 +0,0 @@
#include "waterlevel_sensor.h"
#include <zephyr/kernel.h>
#include <zephyr/logging/log.h>
#include <zephyr/modbus/modbus.h>
#include <stdlib.h>
#include "canbus.h"
LOG_MODULE_REGISTER(wls, CONFIG_LOG_WATERLEVELSENSOR_LEVEL);
#define MODBUS_NODE DT_COMPAT_GET_ANY_STATUS_OKAY(zephyr_modbus_serial)
struct k_thread waterlevel_sensor_thread_data;
K_THREAD_STACK_DEFINE(waterlevel_sensor_stack, WATERLEVEL_SENSOR_STACK_SIZE);
K_MSGQ_DEFINE(waterlevel_sensor_msgq, sizeof(waterlevel_command_t), WATERLEVEL_MESSAGE_QUEUE_SIZE, 4);
static int modbus_client_iface;
volatile static struct
{
int level; // Water level value
int zeropoint; // Minimum value
int maxpoint; // Maximum value
int factor; // Factor for unit conversion
bool factor_set; // Flag to indicate if factor is set
} waterlevel_measurement = {
.factor_set = false,
};
struct modbus_iface_param client_param = {
.mode = MODBUS_MODE_RTU,
.rx_timeout = 50000, // Timeout for receiving data in milliseconds
.serial = {
.baud = 9600,
.parity = UART_CFG_PARITY_NONE,
},
};
static int waterlevel_modbus_init() {
const char iface_name[] = {DEVICE_DT_NAME(MODBUS_NODE)};
modbus_client_iface = modbus_iface_get_by_name(iface_name);
if (modbus_client_iface < 0)
{
LOG_ERR("Failed to get Modbus interface by name: %s", iface_name);
return modbus_client_iface;
}
LOG_DBG("Initializing modbus client interface: %s", iface_name);
return modbus_init_client(modbus_client_iface, client_param);
}
static int waterlevel_modbus_read(void) {
int rc;
union
{
struct
{
int16_t unit; // Unit of measurement (e.g., cm, mm)
int16_t decimals; // Number of decimal places for the measurement
int16_t level; // Water level value
int16_t zeropoint; // Zero point for the measurement
int16_t maxpoint; // Maximum point for the measurement
};
int16_t data[5]; // Data array for holding registers
} waterlevel_modbus_data;
rc = modbus_read_holding_regs(modbus_client_iface, WATERLEVEL_SENSOR_MODBUS_NODE_ID, 0x0002, waterlevel_modbus_data.data, sizeof(waterlevel_modbus_data.data) / sizeof(waterlevel_modbus_data.data[0]));
if (rc < 0)
{
LOG_ERR("Failed to read holding registers, node <%d>, returncode: %d", WATERLEVEL_SENSOR_MODBUS_NODE_ID, rc);
return rc;
}
LOG_DBG("Got values. Unit: %d, Decimals: %d, Level: %d, Zero Point: %d, Max Point: %d",
waterlevel_modbus_data.unit,
waterlevel_modbus_data.decimals,
waterlevel_modbus_data.level,
waterlevel_modbus_data.zeropoint,
waterlevel_modbus_data.maxpoint);
LOG_HEXDUMP_DBG(waterlevel_modbus_data.data, sizeof(waterlevel_modbus_data.data), "Waterlevel Sensor Holding Registers Data");
switch (waterlevel_modbus_data.unit)
{
case 1: // cm
waterlevel_measurement.factor = 10;
break;
case 2: // mm
waterlevel_measurement.factor = 1;
break;
default:
LOG_ERR("Unknown unit: %d", waterlevel_modbus_data.unit);
waterlevel_measurement.factor_set = false;
return -EINVAL;
}
switch (waterlevel_modbus_data.decimals)
{
case 0: // no decimals
waterlevel_measurement.factor /= 1;
break;
case 1: // one decimal
waterlevel_measurement.factor /= 10;
break;
case 2: // two decimals
waterlevel_measurement.factor /= 100;
break;
default:
LOG_ERR("Unknown decimals: %d", waterlevel_modbus_data.decimals);
waterlevel_measurement.factor_set = false;
return -EINVAL;
}
waterlevel_measurement.factor_set = true;
waterlevel_measurement.level = waterlevel_modbus_data.level * waterlevel_measurement.factor;
waterlevel_measurement.zeropoint = waterlevel_modbus_data.zeropoint * waterlevel_measurement.factor;
waterlevel_measurement.maxpoint = waterlevel_modbus_data.maxpoint * waterlevel_measurement.factor;
LOG_DBG("Water level: %dmm, zero point: %dmm, maximum point: %dmm",
waterlevel_measurement.level,
waterlevel_measurement.zeropoint,
waterlevel_measurement.maxpoint);
LOG_HEXDUMP_DBG(waterlevel_modbus_data.data, sizeof(waterlevel_modbus_data.data), "Waterlevel Sensor Holding Registers Data");
return 0;
}
static int waterlevel_send_level(void) {
if (!waterlevel_measurement.factor_set) {
LOG_ERR("Factor not set, cannot send water level");
return -EINVAL;
}
LOG_INF("Sending water level: %dmm", waterlevel_measurement.level);
canbus_send16(CANBUS_REG_WATERLEVEL_LEVEL, waterlevel_measurement.level);
return 0;
}
static int waterlevel_send_zero_point(void) {
if (!waterlevel_measurement.factor_set) {
LOG_ERR("Factor not set, cannot send zero point");
return -EINVAL;
}
LOG_INF("Sending water zero point: %dmm", waterlevel_measurement.zeropoint);
canbus_send16(CANBUS_REG_WATERLEVEL_ZERO_POINT, waterlevel_measurement.zeropoint);
return 0;
}
static int waterlevel_send_max_point(void) {
if (!waterlevel_measurement.factor_set) {
LOG_ERR("Factor not set, cannot send maximum point");
return -EINVAL;
}
LOG_INF("Sending water maximum point: %dmm", waterlevel_measurement.maxpoint);
canbus_send16(CANBUS_REG_WATERLEVEL_MAX_POINT, waterlevel_measurement.maxpoint);
return 0;
}
static int waterlevel_set_zero_point(int zeropoint) {
if (!waterlevel_measurement.factor_set) {
LOG_ERR("Factor not set, cannot set zero point");
return -EINVAL;
}
int16_t zeropoint_modbus = zeropoint / waterlevel_measurement.factor;
int rc = modbus_write_holding_regs(modbus_client_iface, WATERLEVEL_SENSOR_MODBUS_NODE_ID, 0x0005, &zeropoint_modbus, 1);
if (rc < 0) {
LOG_ERR("Failed to write zero point: %d", rc);
return rc;
}
waterlevel_measurement.zeropoint = zeropoint; // Update the local measurement structure
LOG_INF("Zero point set to: %dmm", waterlevel_measurement.zeropoint);
rc = waterlevel_send_zero_point();
if (rc < 0) {
LOG_ERR("Failed to send zero point: %d", rc);
return rc;
}
return 0;
}
static int waterlevel_set_max_point(int maxpoint) {
if (!waterlevel_measurement.factor_set) {
LOG_ERR("Factor not set, cannot set maximum point");
return -EINVAL;
}
int16_t maxpoint_modbus = maxpoint / waterlevel_measurement.factor;
int rc = modbus_write_holding_regs(modbus_client_iface, WATERLEVEL_SENSOR_MODBUS_NODE_ID, 0x0006, &maxpoint_modbus, 1);
if (rc < 0) {
LOG_ERR("Failed to write maximum point: %d", rc);
return rc;
}
waterlevel_measurement.maxpoint = maxpoint; // Update the local measurement structure
LOG_INF("Maximum point set to: %dmm", waterlevel_measurement.maxpoint);
rc = waterlevel_send_max_point();
if (rc < 0) {
LOG_ERR("Failed to send maximum point: %d", rc);
return rc;
}
return 0;
}
void waterlevel_sensor_thread(void *arg1, void *arg2, void *arg3)
{
ARG_UNUSED(arg1);
ARG_UNUSED(arg2);
ARG_UNUSED(arg3);
// Initialize the Modbus client
int rc = waterlevel_modbus_init();
if (rc < 0)
{
LOG_ERR("Failed to initialize Modbus client: %d", rc);
return;
}
rc = waterlevel_modbus_read();
if (rc < 0) {
LOG_ERR("Failed to read initial water level: %d", rc);
return;
}
waterlevel_send_level();
waterlevel_send_zero_point();
waterlevel_send_max_point();
// Initialize the last transmission time and level
// Use k_uptime_get_32() to get the current uptime in milliseconds
// and store the initial water level measurement.
// This will be used to determine when to send updates.
uint32_t last_transmission_time_ms = k_uptime_get_32();
int32_t last_transmission_level = waterlevel_measurement.level;
while (1)
{
uint32_t current_time_ms = k_uptime_get_32();
uint32_t delta_time = current_time_ms-last_transmission_time_ms;
waterlevel_command_t command;
rc = waterlevel_modbus_read();
if (rc < 0)
{
LOG_ERR("Failed to read water level: %d", rc);
continue;
}
if (delta_time >= WATERLEVEL_SENSOR_MAX_UPDATE_INTERVAL_MS ||
abs(waterlevel_measurement.level - last_transmission_level) >= WATERLEVEL_SENSOR_MIN_DELTA) {
rc = waterlevel_send_level();
if (rc < 0) {
LOG_ERR("Failed to send water level: %d", rc);
} else {
last_transmission_time_ms = current_time_ms;
last_transmission_level = waterlevel_measurement.level;
}
}
while (k_msgq_get(&waterlevel_sensor_msgq, &command, K_NO_WAIT) == 0)
{
switch(command.cmd)
{
case WATERLEVEL_CMD_SET:
switch (command.reg)
{
case CANBUS_REG_WATERLEVEL_ZERO_POINT: // Set zero point
rc = waterlevel_set_zero_point(command.data);
if (rc < 0) {
LOG_ERR("Failed to set zero point: %d", rc);
}
break;
case CANBUS_REG_WATERLEVEL_MAX_POINT: // Set maximum point
rc = waterlevel_set_max_point(command.data);
if (rc < 0) {
LOG_ERR("Failed to set maximum point: %d", rc);
}
break;
default:
LOG_ERR("Unknown register for SET command: 0x%02X", command.reg);
break;
}
break;
case WATERLEVEL_CMD_GET:
switch (command.reg)
{
case CANBUS_REG_WATERLEVEL_LEVEL: // Get water level
waterlevel_send_level();
break;
case CANBUS_REG_WATERLEVEL_ZERO_POINT: // Get zero point
waterlevel_send_zero_point();
break;
case CANBUS_REG_WATERLEVEL_MAX_POINT: // Get maximum point
waterlevel_send_max_point();
break;
default:
LOG_ERR("Unknown register for GET command: 0x%02X", command.reg);
break;
}
break;
default:
LOG_ERR("Unknown command type: %d", command.cmd);
break;
}
}
}
}
int waterlevel_sensor_start_thread(void)
{
k_tid_t waterlevel_sensor_thread_id;
// Start the thread
waterlevel_sensor_thread_id = k_thread_create(&waterlevel_sensor_thread_data, waterlevel_sensor_stack,
K_THREAD_STACK_SIZEOF(waterlevel_sensor_stack), waterlevel_sensor_thread,
NULL, NULL, NULL,
WATERLEVEL_SENSOR_THREAD_PRIORITY, 0, K_NO_WAIT);
if (waterlevel_sensor_thread_id == NULL)
{
LOG_ERR("Failed to create water level sensor thread");
return -ENOMEM;
}
k_thread_name_set(waterlevel_sensor_thread_id, "waterlevel_sensor");
LOG_INF("Water level sensor thread started successfully");
return 0;
}
#ifdef CONFIG_SHELL
#include <zephyr/shell/shell.h>
void waterlevel_set_zero_point_shell(const struct shell *shell, size_t argc, char **argv) {
if (argc != 2) {
shell_error(shell, "Usage: waterlevel_sensor set_zero_point <zeropoint>");
return;
}
int zeropoint = atoi(argv[1]);
int rc = waterlevel_set_zero_point(zeropoint);
if (rc < 0) {
shell_error(shell, "Failed to set zero point: %d", rc);
} else {
shell_print(shell, "Zero point set to: %dmm", zeropoint);
}
}
void waterlevel_set_max_point_shell(const struct shell *shell, size_t argc, char **argv) {
if (argc != 2) {
shell_error(shell, "Usage: waterlevel_sensor set_max_point <maxpoint>");
return;
}
int maxpoint = atoi(argv[1]);
int rc = waterlevel_set_max_point(maxpoint);
if (rc < 0) {
shell_error(shell, "Failed to set maximum point: %d", rc);
} else {
shell_print(shell, "Maximum point set to: %dmm", maxpoint);
}
}
void waterlevel_sensor_print_shell(const struct shell *shell, size_t argc, char **argv) {
ARG_UNUSED(argc);
ARG_UNUSED(argv);
waterlevel_modbus_read();
if (!waterlevel_measurement.factor_set) {
shell_error(shell, "Factor not set, cannot print water level");
return;
}
shell_print(shell, "Current water level: %4dmm", waterlevel_measurement.level);
shell_print(shell, "Zero point: %4dmm", waterlevel_measurement.zeropoint);
shell_print(shell, "Maximum point: %4dmm", waterlevel_measurement.maxpoint);
}
// Define the shell commands for the water level sensor
SHELL_STATIC_SUBCMD_SET_CREATE(
waterlevel_sensor_cmds,
SHELL_CMD(print, NULL, "Print the current water level, zero point, and maximum point", waterlevel_sensor_print_shell),
SHELL_CMD(setzero, NULL, "Set the zero point for the water level sensor", waterlevel_set_zero_point_shell),
SHELL_CMD(setmax, NULL, "Set the maximum point for the water level sensor", waterlevel_set_max_point_shell),
SHELL_SUBCMD_SET_END);
SHELL_CMD_REGISTER(wls, &waterlevel_sensor_cmds, "Water level sensor commands", NULL);
#endif // CONFIG_SHELL

View File

@ -1,27 +0,0 @@
#ifndef __WATERLEVEL_SENSOR_H__
#define __WATERLEVEL_SENSOR_H__
#define WATERLEVEL_SENSOR_STACK_SIZE (512)
#define WATERLEVEL_SENSOR_THREAD_PRIORITY (2)
#define WATERLEVEL_MESSAGE_QUEUE_SIZE (5) // Size of the message queue for water level sensor thread
#define WATERLEVEL_SENSOR_READ_INTERVAL_MS (5000) // Interval for reading the water level sensor in milliseconds
#define WATERLEVEL_SENSOR_MIN_DELTA (2) // Minimum change in water level to trigger an update
#define WATERLEVEL_SENSOR_MAX_UPDATE_INTERVAL_MS (600000) // Maximum interval for updating the water level in milliseconds
#define WATERLEVEL_SENSOR_MODBUS_NODE_ID (0x01) // Modbus node ID for the water level sensor
#define WATERLEVEL_SENSOR_MODBUS_BAUD_RATE (9600) // Baud rate for Modbus communication
#include <inttypes.h>
int waterlevel_sensor_start_thread(void);
typedef struct {
uint8_t reg;
enum {
WATERLEVEL_CMD_SET,
WATERLEVEL_CMD_GET,
} cmd;
int16_t data; // Data to be set
} waterlevel_command_t;
#endif // __WATERLEVEL_SENSOR_H__

View File

@ -1,20 +0,0 @@
CONFIG_HAS_MODBUS_WATERLEVEL_SENSOR=y
CONFIG_HAS_VALVE=y
CONFIG_LOG=y
CONFIG_LOG_DEFAULT_LEVEL=3
# CONFIG_LOG_CAN_LEVEL=4
# CONFIG_LOG_WATERLEVELSENSOR_LEVEL=4
# CONFIG_LOG_VALVE_LEVEL=4
CONFIG_CBPRINTF_FP_SUPPORT=y
CONFIG_UART_CONSOLE=y # Console on USART1
# CAN loopback mode for testing
#CONFIG_LOOPBACK_MODE=y
CONFIG_SHELL=y
CONFIG_CAN_SHELL=y
CONFIG_GPIO_SHELL=y
CONFIG_REBOOT=y
CONFIG_ADC=y
CONFIG_ADC_STM32=y

View File

@ -1,53 +0,0 @@
#include <zephyr/logging/log.h>
#include <zephyr/kernel.h>
#include <zephyr/sys/byteorder.h>
#include <zephyr/shell/shell.h>
#include "canbus.h"
#include "canbus_registers.h"
#ifdef CONFIG_HAS_MODBUS_WATERLEVEL_SENSOR
// Include the water level sensor header file when the feature is enabled
#include "waterlevel_sensor.h"
#endif // CONFIG_HAS_MODBUS_WATERLEVEL_SENSOR
#ifdef CONFIG_HAS_VALVE
#include "valve.h"
#endif // CONFIG_HAS_VALVE
LOG_MODULE_REGISTER(main, CONFIG_LOG_DEFAULT_LEVEL);
int main(void)
{
LOG_INF("Starting main application...");
canbus_init();
k_sleep(K_MSEC(3000)); // Allow some time for CAN initialization
#ifdef CONFIG_HAS_MODBUS_WATERLEVEL_SENSOR
int rc = waterlevel_sensor_start_thread();
if (rc < 0)
{
LOG_ERR("Failed to start water level sensor thread: %d", rc);
return rc;
}
#endif // CONFIG_HAS_MODBUS_WATERLEVEL_SENSOR
valve_cmd(VALVE_COMMAND_CLOSE); // Ensure the valve is closed at startup
LOG_INF("Main application started successfully.");
return 0; // Return 0 on success
}
#ifdef CONFIG_SHELL
#include <zephyr/shell/shell.h>
#include <zephyr/sys/reboot.h>
static int reboot_shell_cmd(const struct shell *shell, size_t argc, char **argv)
{
ARG_UNUSED(argc);
ARG_UNUSED(argv);
shell_print(shell, "Rebooting the node in 1 second...");
k_sleep(K_SECONDS(1));
sys_reboot(SYS_REBOOT_COLD);
return 0;
}
SHELL_CMD_REGISTER(reboot, NULL, "Reboot the node", reboot_shell_cmd);
#endif // CONFIG_SHELL

View File

@ -1,86 +0,0 @@
#include <zephyr/kernel.h>
#include <zephyr/drivers/adc.h>
#include <zephyr/logging/log.h>
#include <zephyr/device.h>
#include <zephyr/devicetree.h>
#include <stdint.h>
LOG_MODULE_REGISTER(main2, LOG_LEVEL_DBG);
#define MOTOR_ADC_NODE DT_ALIAS(adc_motor_current)
#define VREF_ADC_NODE DT_ALIAS(adc_vref)
static const struct device * const adc_dev = DEVICE_DT_GET(DT_PARENT(MOTOR_ADC_NODE));
static const uint8_t motor_channel_id = DT_REG_ADDR(MOTOR_ADC_NODE);
static const uint8_t vref_channel_id = DT_REG_ADDR(VREF_ADC_NODE);
int main(void)
{
int err;
int16_t adc_raw_value;
LOG_INF("Starting ADC test with direct register setup...");
if (!device_is_ready(adc_dev)) {
LOG_ERR("ADC device is not ready");
return 0;
}
LOG_INF("Manually setting up ADC registers...");
uint32_t adc_base = DT_REG_ADDR(DT_NODELABEL(adc1));
volatile uint32_t *ADC_CR2 = (uint32_t *)(adc_base + 0x08);
volatile uint32_t *ADC_SMPR1 = (uint32_t *)(adc_base + 0x0C);
volatile uint32_t *ADC_SMPR2 = (uint32_t *)(adc_base + 0x10);
// Schritt 1: Internen VREFINT-Kanal einschalten
const uint32_t ADC_CR2_TSVREFE_BIT = 23;
*ADC_CR2 |= (1 << ADC_CR2_TSVREFE_BIT);
LOG_INF("VREFINT channel enabled via CR2 register.");
// Schritt 2: Lange Abtastzeiten für Stabilität setzen
*ADC_SMPR2 |= (0b111 << (3 * 9));
*ADC_SMPR1 |= (0b111 << (3 * (17 - 10)));
LOG_INF("Acquisition times set directly in SMPR registers.");
k_busy_wait(10);
while (1) {
int32_t motor_raw = 0;
int32_t vref_raw = 0;
struct adc_sequence sequence = {
.buffer = &adc_raw_value,
.buffer_size = sizeof(adc_raw_value),
.resolution = 12,
};
// Motor-Kanal lesen
sequence.channels = BIT(motor_channel_id);
if (adc_read(adc_dev, &sequence) == 0) {
motor_raw = adc_raw_value;
}
// VREF-Kanal lesen
sequence.channels = BIT(vref_channel_id);
if (adc_read(adc_dev, &sequence) == 0) {
vref_raw = adc_raw_value;
}
// VDD-Berechnung mit dem generischen, aber für Sie gut funktionierenden 1200mV-Wert
int32_t vdd_mv = (vref_raw > 0) ? (1200 * 4095 / vref_raw) : 0;
int32_t motor_mv = 0;
if (motor_raw > 0 && vdd_mv > 0) {
motor_mv = motor_raw;
err = adc_raw_to_millivolts(vdd_mv, ADC_GAIN_1, 12, &motor_mv);
}
LOG_INF("Motor Raw: %4d, Motor mV: %4d | VDD: %4d mV", motor_raw, motor_mv, vdd_mv);
k_sleep(K_MSEC(2000));
}
return 0;
}

View File

@ -1,132 +0,0 @@
{
"folders": [
{
"path": "."
}
],
"settings": {
// Hush CMake
"cmake.configureOnOpen": false,
// IntelliSense
"C_Cpp.default.compilerPath": "${userHome}/zephyr-sdk-0.17.1/arm-zephyr-eabi/bin/arm-zephyr-eabi-gcc",
"C_Cpp.default.compileCommands": "${workspaceFolder}/build/compile_commands.json",
// File Associations
"files.associations": {
"waterlevel_sensor.h": "c",
"shell.h": "c",
"can.h": "c"
}
},
"tasks": {
"version": "2.0.0",
"tasks": [
{
"label": "West Build",
"type": "shell",
"group": {
"kind": "build",
"isDefault": true
},
"command": "${userHome}/zephyrproject/.venv/bin/west",
"args": [
"build",
"-p",
"auto",
"-b",
"valve_node"
],
"problemMatcher": [
"$gcc"
],
},
{
"label": "West Configurable Build",
"type": "shell",
"group": {
"kind": "build",
},
"command": "${userHome}/zephyrproject/.venv/bin/west",
"args": [
"build",
"-p",
"${input:pristine}",
"-b",
"${input:board}"
],
"problemMatcher": [
"$gcc"
]
},
{
"label": "West Flash",
"type": "shell",
"command": "${userHome}/zephyrproject/.venv/bin/west",
"args": [
"flash"
],
"problemMatcher": [
"$gcc"
]
}
],
"inputs": [
{
"id": "board",
"type": "promptString",
"default": "vave_node",
"description": "See https://docs.zephyrproject.org/latest/boards/index.html"
},
{
"id": "pristine",
"type": "pickString",
"description": "Choose when to run a pristine build",
"default": "auto",
"options": [
"auto",
"always",
"never"
]
}
]
},
"launch": {
"version": "0.2.0",
"configurations": [
{
"name": "Launch",
"device": "STM32F103RB",
"cwd": "${workspaceFolder}",
"executable": "build/zephyr/zephyr.elf",
"request": "launch",
"type": "cortex-debug",
//"runToEntryPoint": "main",
"servertype": "jlink",
"gdbPath": "${userHome}/zephyr-sdk-0.17.1/arm-zephyr-eabi/bin/arm-zephyr-eabi-gdb",
"preLaunchTask": "West Build"
},
{
"name": "Attach",
"device": "STM32F103RB",
"cwd": "${workspaceFolder}",
"executable": "build/zephyr/zephyr.elf",
"request": "attach",
"type": "cortex-debug",
//"runToEntryPoint": "main",
"servertype": "jlink",
"gdbPath": "${userHome}/zephyr-sdk-0.17.1/arm-zephyr-eabi/bin/arm-zephyr-eabi-gdb"
},
]
},
"extensions": {
"recommendations": [
"ms-vscode.cpptools-extension-pack",
"ms-python.python",
"ms-vscode.vscode-embedded-tools",
"ms-vscode.vscode-serial-monitor",
"marus25.cortex-debug",
"donjayamanne.python-environment-manager"
]
}
}