-
Notifications
You must be signed in to change notification settings - Fork 135
Closed
Description
Issue template
-
Hardware description: Teensy4.1
-
RTOS: No
-
Installation type: Arduino IDE
-
Version or commit hash: humble
Steps to reproduce the issue
(1) Code Behavior Description
- Creating 5 publishers and 5 timers on 1 node to publish ros message
- The code is written based on the examples in micro_ros_arduino/examples/micro-ros_publisher.
- micro_ros_arduino/examples/micro-ros_publisher Keep the contents of the example code and add the following code.
#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;
rcl_publisher_t publisher2; // new
rcl_publisher_t publisher3; // new
rcl_publisher_t publisher4; // new
rcl_publisher_t publisher5; // new
std_msgs__msg__Int32 msg2; // new
std_msgs__msg__Int32 msg3; // new
std_msgs__msg__Int32 msg4; // new
std_msgs__msg__Int32 msg5; // new
rcl_timer_t timer2; // new
rcl_timer_t timer3; // new
rcl_timer_t timer4; // new
rcl_timer_t timer5; // new
#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++;
}
}
// new
void timer_callback2(rcl_timer_t * timer, int64_t last_call_time)
{
RCLC_UNUSED(last_call_time);
if (timer != NULL) {
RCSOFTCHECK(rcl_publish(&publisher2, &msg2, NULL));
msg2.data++;
}
}
// new
void timer_callback3(rcl_timer_t * timer, int64_t last_call_time)
{
RCLC_UNUSED(last_call_time);
if (timer != NULL) {
RCSOFTCHECK(rcl_publish(&publisher3, &msg3, NULL));
msg3.data++;
}
}
// new
void timer_callback4(rcl_timer_t * timer, int64_t last_call_time)
{
RCLC_UNUSED(last_call_time);
if (timer != NULL) {
RCSOFTCHECK(rcl_publish(&publisher4, &msg4, NULL));
msg4.data++;
}
}
// new
void timer_callback5(rcl_timer_t * timer, int64_t last_call_time)
{
RCLC_UNUSED(last_call_time);
if (timer != NULL) {
RCSOFTCHECK(rcl_publish(&publisher5, &msg5, NULL));
msg5.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"));
// new
RCCHECK(rclc_publisher_init_default(
&publisher2,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"publisher2"));
// new
RCCHECK(rclc_publisher_init_default(
&publisher3,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"publisher3"));
// new
RCCHECK(rclc_publisher_init_default(
&publisher4,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"publisher4"));
// new
RCCHECK(rclc_publisher_init_default(
&publisher5,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"publisher5"));
// create timer,
const unsigned int timer_timeout = 1000;
const unsigned int timer_timeout2 = 1000; // new
const unsigned int timer_timeout3 = 1000; // new
const unsigned int timer_timeout4 = 1000; // new
const unsigned int timer_timeout5 = 1000; // new
RCCHECK(rclc_timer_init_default(
&timer,
&support,
RCL_MS_TO_NS(timer_timeout),
timer_callback));
// new
RCCHECK(rclc_timer_init_default(
&timer2,
&support,
RCL_MS_TO_NS(timer_timeout),
timer_callback2));
// new
RCCHECK(rclc_timer_init_default(
&timer3,
&support,
RCL_MS_TO_NS(timer_timeout),
timer_callback3));
// new
RCCHECK(rclc_timer_init_default(
&timer4,
&support,
RCL_MS_TO_NS(timer_timeout),
timer_callback4));
// new
RCCHECK(rclc_timer_init_default(
&timer5,
&support,
RCL_MS_TO_NS(timer_timeout),
timer_callback5));
// create executor
RCCHECK(rclc_executor_init(&executor, &support.context, 5, &allocator)); // new
RCCHECK(rclc_executor_add_timer(&executor, &timer)); // new
RCCHECK(rclc_executor_add_timer(&executor, &timer2)); // new
RCCHECK(rclc_executor_add_timer(&executor, &timer3)); // new
RCCHECK(rclc_executor_add_timer(&executor, &timer4)); // new
RCCHECK(rclc_executor_add_timer(&executor, &timer5)); // new
msg.data = 0;
msg2.data = 0; // new
msg3.data = 0; // new
msg4.data = 0; // new
msg5.data = 0; // new
}
void loop() {
delay(100);
RCSOFTCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)));
}
Expected behavior
- 5 timers publish 5 ROS messages alternately every 1 second.
Actual behavior
- Through the Micro-ROS Agent log, it was confirmed that 5 publishers were created.
- The message is not published, and the error_loop() function is entered, and the LED is turned on/off periodically.
Additional information
- The operating system of the Arduino IDE is Windows 10.
- Question: Is there a parameter inside Micro-ROS to set the Timer to operate normally?
Metadata
Metadata
Assignees
Labels
No labels