|
| 1 | +#include <micro_ros_arduino.h> |
| 2 | + |
| 3 | +#include <stdio.h> |
| 4 | +#include <rcl/rcl.h> |
| 5 | +#include <rcl/error_handling.h> |
| 6 | +#include <rclc/rclc.h> |
| 7 | +#include <rclc/executor.h> |
| 8 | + |
| 9 | +#include <std_msgs/msg/int32.h> |
| 10 | + |
| 11 | +rcl_publisher_t publisher; |
| 12 | +std_msgs__msg__Int32 msg; |
| 13 | +rclc_executor_t executor; |
| 14 | +rclc_support_t support; |
| 15 | +rcl_allocator_t allocator; |
| 16 | +rcl_node_t node; |
| 17 | +rcl_timer_t timer; |
| 18 | + |
| 19 | +#define LED_PIN 13 |
| 20 | + |
| 21 | +#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}} |
| 22 | +#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}} |
| 23 | + |
| 24 | + |
| 25 | +void error_loop(){ |
| 26 | + while(1){ |
| 27 | + digitalWrite(LED_PIN, !digitalRead(LED_PIN)); |
| 28 | + delay(100); |
| 29 | + } |
| 30 | +} |
| 31 | + |
| 32 | +void timer_callback(rcl_timer_t * timer, int64_t last_call_time) |
| 33 | +{ |
| 34 | + RCLC_UNUSED(last_call_time); |
| 35 | + if (timer != NULL) { |
| 36 | + RCSOFTCHECK(rcl_publish(&publisher, &msg, NULL)); |
| 37 | + msg.data++; |
| 38 | + } |
| 39 | +} |
| 40 | + |
| 41 | +void setup() { |
| 42 | + set_microros_transports(); |
| 43 | + |
| 44 | + pinMode(LED_PIN, OUTPUT); |
| 45 | + digitalWrite(LED_PIN, HIGH); |
| 46 | + |
| 47 | + delay(2000); |
| 48 | + |
| 49 | + allocator = rcl_get_default_allocator(); |
| 50 | + |
| 51 | + //create init_options |
| 52 | + RCCHECK(rclc_support_init(&support, 0, NULL, &allocator)); |
| 53 | + |
| 54 | + // create node |
| 55 | + RCCHECK(rclc_node_init_default(&node, "micro_ros_arduino_node", "", &support)); |
| 56 | + |
| 57 | + // create publisher |
| 58 | + RCCHECK(rclc_publisher_init_default( |
| 59 | + &publisher, |
| 60 | + &node, |
| 61 | + ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), |
| 62 | + "micro_ros_arduino_node_publisher")); |
| 63 | + |
| 64 | + // create timer, |
| 65 | + const unsigned int timer_timeout = 1000; |
| 66 | + RCCHECK(rclc_timer_init_default( |
| 67 | + &timer, |
| 68 | + &support, |
| 69 | + RCL_MS_TO_NS(timer_timeout), |
| 70 | + timer_callback)); |
| 71 | + |
| 72 | + // create executor |
| 73 | + RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator)); |
| 74 | + RCCHECK(rclc_executor_add_timer(&executor, &timer)); |
| 75 | + |
| 76 | + msg.data = 0; |
| 77 | +} |
| 78 | + |
| 79 | +void loop() { |
| 80 | + delay(100); |
| 81 | + RCSOFTCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100))); |
| 82 | +} |
0 commit comments