understanding rcl and rclc
I'm a bit at a loss, when reading through the documentation of rcl and rclc on the micro-ros website, it does not clearly state if both a subscriber and publisher need individual rclc_executor and rcl_allocator. Maybe this is crystal clear to other, but I can not find any reference / mention of how to implement both a subscriber and publisher in a single program.
This
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
vs this:
rclc_executor_t pub_executor;
rclc_executor_t sub_executor;
rclc_support_t pub_support;
rclc_support_t sub_support;
rcl_allocator_t pub_allocator;
rcl_allocator_t sub_allocator;
rcl_node_t pub_node;
rcl_node_t sub_node;
The following "combined" publisher and subscriber does Not work. I'm unsure how to properly debug this, as it seems to immediately jump into the error_loop and then it's over. But why it does that, I'm not sure. Below is the merged source code. If any of you has worked with rcl / rclc before and knows what might be worng, please do let me know.
#include <Arduino.h>
#include <micro_ros_platformio.h>
#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <std_msgs/msg/int32.h>
#if !defined(MICRO_ROS_TRANSPORT_ARDUINO_SERIAL)
#error This example is only avaliable for Arduino framework with serial transport.
#endif
rcl_publisher_t publisher;
rcl_subscription_t subscriber;
std_msgs__msg__Int32 msg;
//publisher
rclc_executor_t pub_executor;
rclc_support_t pub_support;
rcl_allocator_t pub_allocator;
rcl_node_t pub_node;
// subscriber
rclc_executor_t sub_executor;
rclc_support_t sub_support;
rcl_allocator_t sub_allocator;
rcl_node_t sub_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)){}}
// Error handle loop
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 subscription_callback(const void * msgin)
{
const std_msgs__msg__Int32 * msg = (const std_msgs__msg__Int32 *)msgin;
digitalWrite(LED_PIN, (msg->data == 0) ? LOW : HIGH);
}
void setup() {
// Configure serial transport
Serial.begin(115200);
set_microros_serial_transports(Serial);
pinMode(LED_PIN, OUTPUT);
digitalWrite(LED_PIN, HIGH);
delay(2000);
sub_allocator = rcl_get_default_allocator();
//create init_options
RCCHECK(rclc_support_init(&pub_support, 0, NULL, &pub_allocator));
RCCHECK(rclc_support_init(&sub_support, 0, NULL, &sub_allocator));
// create node
// RCCHECK(rclc_node_init_default(&sub_node, "micro_ros_platformio_node", "", &sub_support));
RCCHECK(rclc_node_init_default(&pub_node, "uros_platformio_pub_node", "", &pub_support));
RCCHECK(rclc_node_init_default(&sub_node, "uros_platformio_sub_node", "", &sub_support));
// create publisher
RCCHECK(rclc_publisher_init_default(
&publisher,
&pub_node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"micro_ros_platformio_node_publisher"));
// create subscriber
RCCHECK(rclc_subscription_init_default(
&subscriber,
&sub_node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"micro_ros_arduino_subscriber"));
// create timer,
const unsigned int timer_timeout = 1000;
RCCHECK(rclc_timer_init_default(
&timer,
&pub_support,
RCL_MS_TO_NS(timer_timeout),
timer_callback));
// publisher executor
RCCHECK(rclc_executor_init(&pub_executor, &pub_support.context, 1, &pub_allocator));
RCCHECK(rclc_executor_add_timer(&pub_executor, &timer));
//subscriber executor
RCCHECK(rclc_executor_init(&sub_executor, &sub_support.context, 1, &sub_allocator));
RCCHECK(rclc_executor_add_subscription(&sub_executor, &subscriber, &msg, &subscription_callback, ON_NEW_DATA));
msg.data = 0;
}
void loop() {
delay(100);
RCSOFTCHECK(rclc_executor_spin_some(&sub_executor, RCL_MS_TO_NS(100)));
}
BTW: I have converted another example for micro-ROS / micro_ros_platformio on github. It is currently still a pull-request, but once approved and merged it will hopefully help others to get started as well. The link is here: micro-ros_platformio/examples
Once I successfully create an example of a single program with subscriber and publisher I will create another pull-request to the github repository.
Thanks guys, appreciate any replies and especially hints / pointers in the right direction
please correct me if I'm way off: executor, support and allocator are shared. the problem most likely is
Here are the issue I believe are with the code snippet above: the order is wrong rclc_executor_init needs to be the first statement, followed by rclc_executor_add_<whaterver needs="" adding="">
is this correct?