Skip to content

Commit 96a6bb5

Browse files
committed
Added examples
1 parent 846343d commit 96a6bb5

File tree

2 files changed

+160
-0
lines changed

2 files changed

+160
-0
lines changed
Lines changed: 87 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,87 @@
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)){error_loop();}}
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+
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+
43+
pinMode(LED_PIN, OUTPUT);
44+
digitalWrite(LED_PIN, HIGH);
45+
46+
delay(2000);
47+
48+
allocator = rcl_get_default_allocator();
49+
50+
//create init_options
51+
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
52+
53+
// create node
54+
node = rcl_get_zero_initialized_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+
timer = rcl_get_zero_initialized_timer();
66+
const unsigned int timer_timeout = 1000;
67+
RCCHECK(rclc_timer_init_default(
68+
&timer,
69+
&support,
70+
RCL_MS_TO_NS(timer_timeout),
71+
timer_callback));
72+
73+
// create executor
74+
executor = rclc_executor_get_zero_initialized_executor();
75+
RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
76+
77+
unsigned int rcl_wait_timeout = 100; // in ms
78+
RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout)));
79+
RCCHECK(rclc_executor_add_timer(&executor, &timer));
80+
81+
msg.data = 0;
82+
}
83+
84+
void loop() {
85+
delay(100);
86+
RCCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)));
87+
}
Lines changed: 73 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,73 @@
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_subscription_t subscriber;
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)){error_loop();}}
23+
24+
25+
void error_loop(){
26+
while(1){
27+
digitalWrite(LED_PIN, !digitalRead(LED_PIN));
28+
delay(100);
29+
}
30+
}
31+
32+
void subscription_callback(const void * msgin)
33+
{
34+
const std_msgs__msg__Int32 * msg = (const std_msgs__msg__Int32 *)msgin;
35+
digitalWrite(LED_PIN, (msg->data == 0) ? LOW : HIGH);
36+
}
37+
38+
void setup() {
39+
40+
pinMode(LED_PIN, OUTPUT);
41+
digitalWrite(LED_PIN, HIGH);
42+
43+
delay(2000);
44+
45+
allocator = rcl_get_default_allocator();
46+
47+
//create init_options
48+
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
49+
50+
// create node
51+
node = rcl_get_zero_initialized_node();
52+
RCCHECK(rclc_node_init_default(&node, "micro_ros_arduino_node", "", &support));
53+
54+
// create subscriber
55+
RCCHECK(rclc_subscription_init_default(
56+
&subscriber,
57+
&node,
58+
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
59+
"micro_ros_arduino_subscriber"));
60+
61+
// create executor
62+
executor = rclc_executor_get_zero_initialized_executor();
63+
RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
64+
65+
unsigned int rcl_wait_timeout = 1000; // in ms
66+
RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout)));
67+
RCCHECK(rclc_executor_add_subscription(&executor, &subscriber, &msg, &subscription_callback, ON_NEW_DATA));
68+
}
69+
70+
void loop() {
71+
delay(100);
72+
RCCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)));
73+
}

0 commit comments

Comments
 (0)