-
Notifications
You must be signed in to change notification settings - Fork 0
/
main.c
100 lines (81 loc) · 2.69 KB
/
main.c
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
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
#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>
#include <rmw_microros/rmw_microros.h>
#include "pico/stdlib.h"
#include "pico_uart_transports.h"
#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){printf("Failed status on line %d: %d. Aborting.\n",__LINE__,(int)temp_rc); return 1;}}
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){printf("Failed status on line %d: %d. Continuing.\n",__LINE__,(int)temp_rc);}}
#define LED_PIN 25
rcl_publisher_t publisher;
rcl_subscription_t subscriber;
std_msgs__msg__Int32 send_msg;
std_msgs__msg__Int32 recv_msg;
void timer_callback(rcl_timer_t * timer, int64_t last_call_time)
{
(void) last_call_time;
if (timer != NULL) {
RCSOFTCHECK(rcl_publish(&publisher, &send_msg, NULL));
printf("Sent: %d\n", send_msg.data);
send_msg.data++;
}
}
void subscription_callback(const void * msgin)
{
const std_msgs__msg__Int32 * msg = (const std_msgs__msg__Int32 *)msgin;
printf("Received: %d\n", msg->data);
}
int main(int argc, const char * const * argv)
{
rmw_uros_set_custom_transport(
true,
NULL,
pico_serial_transport_open,
pico_serial_transport_close,
pico_serial_transport_write,
pico_serial_transport_read
);
gpio_init(LED_PIN);
gpio_set_dir(LED_PIN, GPIO_OUT);
rcl_allocator_t allocator = rcl_get_default_allocator();
rclc_support_t support;
// create init_options
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
// create node
rcl_node_t node;
RCCHECK(rclc_node_init_default(&node, "int32_publisher_subscriber_rclc", "", &support));
// create publisher
RCCHECK(rclc_publisher_init_default(
&publisher,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"int32_publisher"));
// create subscriber
RCCHECK(rclc_subscription_init_default(
&subscriber,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"int32_subscriber"));
// create timer,
rcl_timer_t timer;
const unsigned int timer_timeout = 1000;
RCCHECK(rclc_timer_init_default(
&timer,
&support,
RCL_MS_TO_NS(timer_timeout),
timer_callback));
// create executor
rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
RCCHECK(rclc_executor_init(&executor, &support.context, 2, &allocator));
RCCHECK(rclc_executor_add_timer(&executor, &timer));
RCCHECK(rclc_executor_add_subscription(&executor, &subscriber, &recv_msg, &subscription_callback, ON_NEW_DATA));
send_msg.data = 0;
gpio_put(LED_PIN, 1);
rclc_executor_spin(&executor);
RCCHECK(rcl_subscription_fini(&subscriber, &node));
RCCHECK(rcl_publisher_fini(&publisher, &node));
RCCHECK(rcl_node_fini(&node));
}