Micro-ROS Publisher
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
#include <micro_ros_arduino.h> 
#include <stdio.h>
#include <rcl/rcl.h>
#include <rcl/error_handling.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <std_msgs/msg/int32.h>
rcl_publisher_t publisher;
std_msgs__msg__Int32 msg;
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
rcl_timer_t timer;
#define LED_PIN 13
#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}}
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}}
void error_loop(){
  while(1){
    digitalWrite(LED_PIN, !digitalRead(LED_PIN));
    delay(100);
  }
}
void timer_callback(rcl_timer_t * timer, int64_t last_call_time)
{  
  RCLC_UNUSED(last_call_time);
  if (timer != NULL) {
    RCSOFTCHECK(rcl_publish(&publisher, &msg, NULL));
    msg.data++;
  }
}
void setup() {
  set_microros_transports();
  
  pinMode(LED_PIN, OUTPUT);
  digitalWrite(LED_PIN, HIGH);  
  
  delay(2000);
  allocator = rcl_get_default_allocator();
  //create init_options
  RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
  // create node
  RCCHECK(rclc_node_init_default(&node, "micro_ros_arduino_node", "", &support));
  // create publisher
  RCCHECK(rclc_publisher_init_default(
    &publisher,
    &node,
    ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
    "micro_ros_arduino_node_publisher"));
  // create timer,
  const unsigned int timer_timeout = 1000;
  RCCHECK(rclc_timer_init_default(
    &timer,
    &support,
    RCL_MS_TO_NS(timer_timeout),
    timer_callback));
  // create executor
  RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
  RCCHECK(rclc_executor_add_timer(&executor, &timer));
  msg.data = 0;
}
void loop() {
  delay(100);
  RCSOFTCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)));
}
1
2
3
4
5
6
#include <micro_ros_arduino.h>
#include <rcl/rcl.h>
#include <rcl/error_handling.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <std_msgs/msg/int32.h>
- micro_ros_arduino.h: Includes Micro-ROS Arduino-specific functions.
- rcl/rcl.h and rclc: Provides core ROS client library (RCL) and RCLC utilities.
- std_msgs/msg/int32.h: Includes the ROS std_msgs::msg::Int32message type for publishing integers.
1
2
3
4
5
6
7
rcl_publisher_t publisher;
std_msgs__msg__Int32 msg;
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
rcl_timer_t timer;
- executor: Manages callbacks (like timers).
- support: Manages initialization options for Micro-ROS.
- allocator: Allocates memory for the Micro-ROS framework.
- node: A Micro-ROS node (basic ROS entity that performs tasks).
- timer: Periodically triggers the timer_callback.
1
2
3
#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}}
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}}
- RCCHECK: Ensures critical operations succeed. If an error occurs, it enters the error_loop.
- RCSOFTCHECK: Similar, but doesn’t halt execution on failure.
1
2
3
4
5
6
void error_loop(){
  while(1){
    digitalWrite(LED_PIN, !digitalRead(LED_PIN));
    delay(100);
  }
}
- Blinks the onboard LED continuously to indicate an error.
1
2
3
4
5
6
7
8
void timer_callback(rcl_timer_t * timer, int64_t last_call_time)
{  
  RCLC_UNUSED(last_call_time);
  if (timer != NULL) {
    RCSOFTCHECK(rcl_publish(&publisher, &msg, NULL));
    msg.data++;
  }
}
- This function is called each time the timer triggers.
- Increments msg.dataand publishes it to the topic.
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
void setup() {
  set_microros_transports();  // Initialize communication (e.g., Serial, WiFi, etc.)
  pinMode(LED_PIN, OUTPUT);   // Set LED_PIN as output.
  digitalWrite(LED_PIN, HIGH);  
  delay(2000);  // Wait for 2 seconds for initialization.
  allocator = rcl_get_default_allocator();  // Set up the memory allocator.
  // Initialize Micro-ROS support and components
  RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
  RCCHECK(rclc_node_init_default(&node, "micro_ros_arduino_node", "", &support));
  RCCHECK(rclc_publisher_init_default(
    &publisher,
    &node,
    ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
    "micro_ros_arduino_node_publisher"));
  const unsigned int timer_timeout = 1000; // Timer interval in milliseconds.
  RCCHECK(rclc_timer_init_default(
    &timer,
    &support,
    RCL_MS_TO_NS(timer_timeout),
    timer_callback));
  RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
  RCCHECK(rclc_executor_add_timer(&executor, &timer));
  msg.data = 0;  // Initialize the message value.
}
Key setup steps:
- Transport Setup: Configures the communication method (e.g., serial or WiFi).
- Micro-ROS Initialization:- Initializes the support structure.
- Creates a node ("micro_ros_arduino_node").
- Sets up the publisher for the topic "micro_ros_arduino_node_publisher".
 
- Timer Setup: Calls timer_callbackevery second (1000 ms).
- Executor Setup: Manages the timer callback execution.
- Message Initialization: Starts with msg.data = 0.
1
2
3
4
void loop() {
  delay(100);  // Short delay.
  RCSOFTCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)));
}
- The executor handles the timer callback, ensuring timer_callbackis executed as needed.
RCL
Common Types and Return Codes
- rcl_ret_t: The type that holds an rcl return code
- Codes:- RCL_RET_OK: Success return code
- RCL_RET_ERROR: Unspecified error return code
- RCL_RET_NOT_INIT: rcl_init() not yet called return code
- RCL_RET_
 
Allocator
- rcl_allocator_t: Encapsulation of an allocator
- RCL_CHECK_ALLOCATOR: Check that the given allocator is initialized. If the allocator is not initialized, run the fail_statement
- RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, msg, fail_statement): Check that the given allocator is initialized, or fail with a message. If the allocator is not initialized, set the error to msg, and run the fail_statement
- rcl_get_default_allocator: Return a properly initialized rcl_allocator_t with default values
1
2
3
4
rcl_allocator_t allocator = rcl_get_default_allocator();
if (!allocator.allocate) {
    printf("Allocator not initialized\n");
}
Timer
- rcl_timer_t: Structure which encapsulates a ROS Timer
- Macros:- RCL_MS_TO_NS: Convenience macro to convert milliseconds to nanoseconds
 
- rcl_timer_init: Initializes a timer with a callback- 1 2 3 4 5 6 7 8 - rcl_ret_t rcl_timer_init( rcl_timer_t *timer, rcl_clock_t *clock, rcl_context_t *context, int64_t period, const rcl_timer_callback_t callback, rcl_allocator_t allocator ) 
Publisher
- rcl_publisher_t: Structure which encapsulates a ROS Publisher
- Initialization: - 1 2 3 4 5 6 7 - rcl_ret_t rcl_publisher_init( rcl_publisher_t *publisher, const rcl_node_t *node, const rosidl_message_type_support_t *type_support, const char *topic_name, const rcl_publisher_options_t *options ) 
- Publish messages: - 1 2 3 4 5 - rcl_ret_t rcl_publish( const rcl_publisher_t *publisher, const void *ros_message, rmw_publisher_allocation_t *allocation ) 
- Stop publisher: After calling, the node will no longer be advertising that it is publishing on this topic (assuming this is the only publisher on this topic) - 1 2 3 4 - rcl_ret_t rcl_publisher_fini( const rcl_publisher_t *publisher, const rcl_node_t *node ) 
Node
- rcl_node_t: Structure which encapsulates a ROS Node
- rcl_node_impl_t
- rcl_service_t
- Initialization: - 1 2 3 4 5 6 7 - rcl_ret_t rcl_node_init( rcl_node_t *node, const char *name, const char *namespace_, rcl_context_t *context, const rcl_node_options_t *options ) 
- rcl_ret_t rcl_node_fini(rcl_node_t *node): Destroys any automatically created infrastructure and deallocates memory. After calling, the rcl_node_t can be safely deallocated
RCLC
Support
- RCLC_UNUSED
- rclc_support_t: Initializes RCL and creates foundational data structures
- rclc_support_init: Initializes rcl and creates some support data structures. Initializes clock as RCL_STEADY_TIME- 1 2 3 4 5 6 - rcl_ret_t rclc_support_init( rclc_support_t *support, int argc, char const *const *argv, rcl_allocator_t *allocator ) 
Node
- rcl_node_t: Structure which encapsulates a ROS Node
- rclc_node_init_default: Creates a default RCL node- 1 2 3 4 5 6 - rcl_ret_t rclc_node_init_default( rcl_node_t *node, const char *name, const char *namespace_, rclc_support_t *support ) 
Timer
- rcl_timer_t: Structure which encapsulates a ROS Timer
- rclc_timer_init_default: Creates an rcl timer- 1 2 3 4 5 6 - rcl_ret_t rclc_timer_init_default( rcl_timer_t *timer, rclc_support_t *support, const uint64_t timeout_ns, const rcl_timer_callback_t callback ) 
Executor
- rclc_executor_t: Handles callback execution for nodes, timers, and other handles
- Initialization: - 1 2 3 4 5 6 - rcl_ret_t rclc_executor_init( rclc_executor_t *executor, rcl_context_t *context, const size_t number_of_handles, const rcl_allocator_t *allocator ) 
- Add Timer to Executor: Adds time to an executor - 1 2 3 4 - rcl_ret_t rclc_executor_add_timer( rclc_executor_t *executor, rcl_timer_t *timer ) 
Publisher
- rclc_publisher_init_default: Creates an rcl publisher- 1 2 3 4 5 6 - rcl_ret_t rclc_publisher_init_default( rcl_publisher_t *publisher, const rcl_node_t *node, const rosidl_message_type_support_t *type_support, const char *topic_name ) 
Quick Initialization Flow
- Support Initialization: - 1 2 - rclc_support_t support; rclc_support_init(&support, argc, argv, &allocator); 
- Node Initialization: - 1 2 - rcl_node_t node; rclc_node_init_default(&node, "node_name", "namespace", &support); 
- Publisher Creation: - 1 2 - rcl_publisher_t publisher; rclc_publisher_init_default(&publisher, &node, type_support, "topic_name"); 
- Timer and Executor: - 1 2 3 4 5 6 - rcl_timer_t timer; rclc_timer_init_default(&timer, &support, RCL_MS_TO_NS(1000), my_callback); rclc_executor_t executor; rclc_executor_init(&executor, &support.context, 1, &allocator); rclc_executor_add_timer(&executor, &timer); 
