Skip to content
Merged
Show file tree
Hide file tree
Changes from 9 commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ jobs:
strategy:
fail-fast: false
matrix:
platform: [teensy41, teensy40, teensy36, teensy35, teensy31, due, zero, olimex_e407, esp32dev, nanorp2040connect, portenta_h7_m7, teensy41_eth, nanorp2040connect_wifi, portenta_h7_m7_wifi, esp32dev_wifi, portenta_h7_m7_humble, portenta_h7_m7_jazzy, portenta_h7_m7_rolling, teensy41_custom, pico]
platform: [teensy41, teensy40, teensy36, teensy35, teensy31, due, zero, olimex_e407, esp32dev, nanorp2040connect, portenta_h7_m7, teensy41_eth, nanorp2040connect_wifi, portenta_h7_m7_wifi, esp32dev_wifi, esp32dev_ethernet, portenta_h7_m7_humble, portenta_h7_m7_jazzy, portenta_h7_m7_rolling, teensy41_custom, pico]

steps:
- uses: actions/checkout@v3
Expand Down
37 changes: 25 additions & 12 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -28,18 +28,18 @@ PlatformIO will handle the full build process, including dependencies, compilati
## Supported boards
Supported boards are:

| Board | Platform | Framework | Transports | Default meta file |
| -------------------------------------------- | ------------- | ----------- | -------------------------------- | ------------------------ |
| `portenta_h7_m7` | `ststm32` | `arduino` | `serial` <br/> `wifi` | `colcon.meta` |
| `teensy41` | `teensy` | `arduino` | `serial` <br/> `native_ethernet` | `colcon.meta` |
| `teensy40` | `teensy` | `arduino` | `serial` | `colcon.meta` |
| `teensy36` <br/> `teensy35` <br/> `teensy31` | `teensy` | `arduino` | `serial` | `colcon_lowmem.meta` |
| `due` | `atmelsam` | `arduino` | `serial` | `colcon_verylowmem.meta` |
| `zero` | `atmelsam` | `arduino` | `serial` | `colcon_verylowmem.meta` |
| `olimex_e407` | `ststm32` | `arduino` | `serial` | `colcon.meta` |
| `esp32dev` | `espressif32` | `arduino` | `serial` <br/> `wifi` | `colcon.meta` |
| `nanorp2040connect` | `raspberrypi` | `arduino` | `serial` <br/> `wifi_nina` | `colcon_verylowmem.meta` |
| `pico` | `raspberrypi` | `arduino` | `serial` | `colcon.meta`|
| Board | Platform | Framework | Transports | Default meta file |
| -------------------------------------------- | ------------- | ----------- | ---------------------------------------- | ------------------------ |
| `portenta_h7_m7` | `ststm32` | `arduino` | `serial` <br/> `wifi` | `colcon.meta` |
| `teensy41` | `teensy` | `arduino` | `serial` <br/> `native_ethernet` | `colcon.meta` |
| `teensy40` | `teensy` | `arduino` | `serial` | `colcon.meta` |
| `teensy36` <br/> `teensy35` <br/> `teensy31` | `teensy` | `arduino` | `serial` | `colcon_lowmem.meta` |
| `due` | `atmelsam` | `arduino` | `serial` | `colcon_verylowmem.meta` |
| `zero` | `atmelsam` | `arduino` | `serial` | `colcon_verylowmem.meta` |
| `olimex_e407` | `ststm32` | `arduino` | `serial` | `colcon.meta` |
| `esp32dev` | `espressif32` | `arduino` | `serial` <br/> `wifi` <br/> `ethernet` | `colcon.meta` |
| `nanorp2040connect` | `raspberrypi` | `arduino` | `serial` <br/> `wifi_nina` | `colcon_verylowmem.meta` |
| `pico` | `raspberrypi` | `arduino` | `serial` | `colcon.meta` |

The community is encouraged to open pull request with custom use cases.

Expand Down Expand Up @@ -133,6 +133,19 @@ The transport can be configured with the `board_microros_transport = <transport>
set_microros_native_ethernet_transports(local_mac, local_ip, agent_ip, agent_port);
```

- `ethernet`

```c
IPAddress client_ip(192, 168, 1, 177);
IPAddress gateway(192, 168, 1, 1);
IPAddress netmask(255, 255, 255, 0);
IPAddress agent_ip(192, 168, 1, 113);
size_t agent_port = 8888;

// Optional hostname, defaults to nullptr (no hostname set)
set_microros_ethernet_transports(client_ip, gateway, netmask, agent_ip, agent_port, "my-microros-device");
```

- `custom`

The user will need to write transport functions in app code and provide it to the micro-ROS library using [`rmw_uros_set_custom_transport()` API](https://micro.ros.org/docs/tutorials/advanced/create_custom_transports/)
Expand Down
8 changes: 8 additions & 0 deletions ci/platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,14 @@ board_microros_transport = native_ethernet
lib_deps =
../

[env:esp32dev_ethernet]
platform = espressif32
board = esp32dev
framework = arduino
board_microros_transport = ethernet
lib_deps =
../

; WiFi platforms

[env:portenta_h7_m7_wifi]
Expand Down
10 changes: 10 additions & 0 deletions ci/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

#if defined(MICRO_ROS_TRANSPORT_ARDUINO_WIFI)
#include <WiFi.h>
#elif defined(MICRO_ROS_TRANSPORT_ARDUINO_ETHERNET)
#include <ETH.h>
#endif

#include <micro_ros_platformio.h>
Expand Down Expand Up @@ -78,6 +80,14 @@ void setup() {
char psk[]= "WIFI_PSK";

set_microros_wifi_transports(ssid, psk, agent_ip, agent_port);
#elif defined(MICRO_ROS_TRANSPORT_ARDUINO_ETHERNET)
IPAddress local_ip(192, 168, 1, 177);
IPAddress gateway(192, 168, 1, 1);
IPAddress netmask(255, 255, 255, 0);
IPAddress agent_ip(192, 168, 1, 113);
size_t agent_port = 8888;

set_microros_ethernet_transports(local_ip, gateway, netmask, agent_ip, agent_port, "micro-ros-eth");
#elif defined(MICRO_ROS_TRANSPORT_ARDUINO_CUSTOM)
rmw_uros_set_custom_transport(
MICROROS_TRANSPORTS_FRAMING_MODE,
Expand Down
33 changes: 33 additions & 0 deletions examples/docker-compose.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
version: "2.1"

services:
micro-ros-agent:
image: microros/micro-ros-agent:humble
container_name: micro-ros-agent
network_mode: host
stdin_open: true
tty: true
environment:
- ROS_DOMAIN_ID=8
ports:
- 8888:8888/udp
command: udp4 --port 8888 --verbose 6

rqt:
image: osrf/ros:humble-desktop
container_name: rqt-visualizer
network_mode: host
ipc: host
pid: host
tty: true
privileged: true
device_cgroup_rules:
- 'c 189:* rmw'
environment:
- ROS_DOMAIN_ID=8
- DISPLAY=${DISPLAY}
- QT_X11_NO_MITSHM=1
volumes:
- /tmp/.X11-unix:/tmp/.X11-unix:rw
command: bash -c "source /opt/ros/humble/setup.bash && rqt"

8 changes: 8 additions & 0 deletions examples/ethernet_pubsub/platformio.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
[env:esp32dev]
platform = espressif32
board = esp32dev
framework = arduino
board_microros_transport = ethernet
monitor_speed = 115200
lib_deps =
https://github.com/micro-ROS/micro_ros_platformio
235 changes: 235 additions & 0 deletions examples/ethernet_pubsub/src/main.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,235 @@
#define ETH_PHY_POWER 5
#define ETH_PHY_MDC 23
#define ETH_PHY_MDIO 18
#define ETH_PHY_TYPE ETH_PHY_LAN8720
#define ETH_PHY_ADDR 0
#define ETH_CLK_MODE ETH_CLOCK_GPIO17_OUT

#include <Arduino.h>
#include <micro_ros_platformio.h>
#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <std_msgs/msg/string.h>

// Network configuration
const IPAddress kClientIP(10, 4, 4, 177);
const IPAddress kGateway(10, 4, 4, 1);
const IPAddress kNetmask(255, 255, 255, 0);
const IPAddress kAgentIP(10, 4, 4, 187);
const uint16_t kAgentPort = 8888;
const char* kHostname = "micro-ros-eth";

// ROS node configuration
const char* kNodeName = "eth_pubsub_node";
const char* kPublisherTopic = "micro_ros_response";
const char* kSubscriberTopic = "micro_ros_name";
const int kExecutorTimeout = 100; // ms
const size_t kDomainId = 8; // ROS domain ID

// ROS entities
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
rcl_publisher_t publisher;
rcl_subscription_t subscriber;
rcl_timer_t timer;

// Message buffers
std_msgs__msg__String received_msg;
std_msgs__msg__String response_msg;
char received_buffer[50];
char response_buffer[100];

// Connection management
enum class ConnectionState {
kInitializing,
kWaitingForAgent,
kConnecting,
kConnected,
kDisconnected
};
ConnectionState connection_state = ConnectionState::kInitializing;

// Forward declarations
void HandleConnectionState();
void SubscriptionCallback(const void* msgin);
void PublishResponse();
bool CreateEntities();
void DestroyEntities();

// Ethernet event callback
void OnEthernetEvent(arduino_event_id_t event, void* event_info) {
switch (event) {
case ARDUINO_EVENT_ETH_CONNECTED:
Serial.println("[ETH] Connected");
break;

case ARDUINO_EVENT_ETH_DISCONNECTED:
Serial.println("[ETH] Disconnected");
break;

case ARDUINO_EVENT_ETH_GOT_IP:
Serial.print("[ETH] Got IP: ");
Serial.println(*(IPAddress*)event_info);
break;

default:
break;
}
}

void setup() {
Serial.begin(115200);
Serial.println("[INIT] Starting micro-ROS node...");

// Initialize message buffers
received_msg.data.data = received_buffer;
received_msg.data.capacity = sizeof(received_buffer);
response_msg.data.data = response_buffer;
response_msg.data.capacity = sizeof(response_buffer);

// Initialize micro-ROS transport with unified callback
set_microros_ethernet_transports(
kClientIP, kGateway, kNetmask, kAgentIP, kAgentPort,
kHostname, OnEthernetEvent
);

delay(2000);
connection_state = ConnectionState::kWaitingForAgent;
}

void loop() {
HandleConnectionState();
delay(100); // Prevent tight loop
}

void HandleConnectionState() {
switch (connection_state) {
case ConnectionState::kWaitingForAgent:
if (RMW_RET_OK == rmw_uros_ping_agent(200, 3)) {
Serial.println("[ROS] Agent found, establishing connection...");
connection_state = ConnectionState::kConnecting;
}
break;

case ConnectionState::kConnecting:
if (CreateEntities()) {
Serial.println("[ROS] Connected and ready!");
connection_state = ConnectionState::kConnected;
} else {
Serial.println("[ROS] Connection failed, retrying...");
connection_state = ConnectionState::kWaitingForAgent;
}
break;

case ConnectionState::kConnected:
if (RMW_RET_OK != rmw_uros_ping_agent(200, 3)) {
Serial.println("[ROS] Agent disconnected!");
connection_state = ConnectionState::kDisconnected;
} else {
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(kExecutorTimeout));
}
break;

case ConnectionState::kDisconnected:
DestroyEntities();
Serial.println("[ROS] Waiting for agent...");
connection_state = ConnectionState::kWaitingForAgent;
break;

default:
break;
}
}

void SubscriptionCallback(const void* msgin) {
const std_msgs__msg__String* msg = (const std_msgs__msg__String*)msgin;
Serial.print("[SUB] Received: ");
Serial.println(msg->data.data);

// Create response message: "Hello <received_name>!"
snprintf(response_buffer, sizeof(response_buffer), "Hello %s!", msg->data.data);
response_msg.data.size = strlen(response_buffer);

// Publish response
PublishResponse();
}

void PublishResponse() {
rcl_ret_t ret = rcl_publish(&publisher, &response_msg, NULL);
if (ret == RCL_RET_OK) {
Serial.print("[PUB] Published: ");
Serial.println(response_msg.data.data);
} else {
Serial.println("[PUB] Error publishing message");
}
}

bool CreateEntities() {
allocator = rcl_get_default_allocator();

// Initialize options and set domain ID
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
if (rcl_init_options_init(&init_options, allocator) != RCL_RET_OK) {
return false;
}
if (rcl_init_options_set_domain_id(&init_options, kDomainId) != RCL_RET_OK) {
return false;
}

// Initialize support with domain ID options
if (rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator) != RCL_RET_OK) {
return false;
}

// Clean up initialization options
if (rcl_init_options_fini(&init_options) != RCL_RET_OK) {
return false;
}

// Initialize node and rest of entities
if (rclc_node_init_default(&node, kNodeName, "", &support) != RCL_RET_OK) {
return false;
}

// Create publisher
if (rclc_publisher_init_default(&publisher, &node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String),
kPublisherTopic) != RCL_RET_OK) {
return false;
}

// Create subscriber
if (rclc_subscription_init_default(&subscriber, &node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String),
kSubscriberTopic) != RCL_RET_OK) {
return false;
}

// Initialize executor
if (rclc_executor_init(&executor, &support.context, 1, &allocator) != RCL_RET_OK) {
return false;
}

// Add subscriber to executor
if (rclc_executor_add_subscription(&executor, &subscriber, &received_msg,
&SubscriptionCallback, ON_NEW_DATA) != RCL_RET_OK) {
return false;
}

return true;
}

void DestroyEntities() {
rmw_context_t* rmw_context = rcl_context_get_rmw_context(&support.context);
(void)rmw_uros_set_context_entity_destroy_session_timeout(rmw_context, 0);

rcl_ret_t rc = RCL_RET_OK;
rc = rcl_subscription_fini(&subscriber, &node);
rc = rcl_publisher_fini(&publisher, &node);
rclc_executor_fini(&executor);
rc = rcl_node_fini(&node);
rclc_support_fini(&support);
}
Loading
Loading