1
+ /* *
2
+ * ROS driver for controlling the Arduino Braccio++ with ROS2.
3
+ */
4
+
5
+ /* *************************************************************************************
6
+ * INCLUDE
7
+ **************************************************************************************/
8
+
1
9
#include < micro_ros_arduino.h>
2
10
3
11
#include < stdio.h>
8
16
9
17
#include < std_msgs/msg/int32.h>
10
18
19
+ /* *************************************************************************************
20
+ * GLOBAL VARIABLES
21
+ **************************************************************************************/
22
+
11
23
rcl_publisher_t publisher;
12
24
std_msgs__msg__Int32 msg;
13
25
rclc_executor_t executor;
@@ -16,29 +28,21 @@ rcl_allocator_t allocator;
16
28
rcl_node_t node;
17
29
rcl_timer_t timer;
18
30
31
+ /* *************************************************************************************
32
+ * DEFINES
33
+ **************************************************************************************/
34
+
19
35
#define LED_PIN 13
20
36
21
37
#define RCCHECK (fn ) { rcl_ret_t temp_rc = fn; if ((temp_rc != RCL_RET_OK)){error_loop ();}}
22
38
#define RCSOFTCHECK (fn ) { rcl_ret_t temp_rc = fn; if ((temp_rc != RCL_RET_OK)){}}
23
39
40
+ /* *************************************************************************************
41
+ * SETUP/LOOP
42
+ **************************************************************************************/
24
43
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 () {
44
+ void setup ()
45
+ {
42
46
set_microros_transports ();
43
47
44
48
pinMode (LED_PIN, OUTPUT);
@@ -48,35 +52,59 @@ void setup() {
48
52
49
53
allocator = rcl_get_default_allocator ();
50
54
51
- // create init_options
55
+ /* Create init_options. */
52
56
RCCHECK (rclc_support_init (&support, 0 , NULL , &allocator));
53
57
54
- // create node
55
- RCCHECK (rclc_node_init_default (&node, " micro_ros_arduino_node " , " " , &support));
58
+ /* Create node. */
59
+ RCCHECK (rclc_node_init_default (&node, " braccio_plusplus_node " , " " , &support));
56
60
57
- // create publisher
61
+ /* Create JointState publisher. */
58
62
RCCHECK (rclc_publisher_init_default (
59
63
&publisher,
60
64
&node,
61
65
ROSIDL_GET_MSG_TYPE_SUPPORT (std_msgs, msg, Int32),
62
- " micro_ros_arduino_node_publisher " ));
66
+ " braccio_plusplus_node_joint_state_publisher " ));
63
67
64
- // create timer,
68
+ /* Create Timer. */
65
69
const unsigned int timer_timeout = 1000 ;
66
70
RCCHECK (rclc_timer_init_default (
67
71
&timer,
68
72
&support,
69
73
RCL_MS_TO_NS (timer_timeout),
70
74
timer_callback));
71
75
72
- // create executor
76
+ /* Create executor. */
73
77
RCCHECK (rclc_executor_init (&executor, &support.context , 1 , &allocator));
74
78
RCCHECK (rclc_executor_add_timer (&executor, &timer));
75
79
76
80
msg.data = 0 ;
77
81
}
78
82
79
- void loop () {
83
+ void loop ()
84
+ {
80
85
delay (100 );
81
86
RCSOFTCHECK (rclc_executor_spin_some (&executor, RCL_MS_TO_NS (100 )));
82
87
}
88
+
89
+ /* *************************************************************************************
90
+ * FUNCTIONS
91
+ **************************************************************************************/
92
+
93
+ void error_loop ()
94
+ {
95
+ for (;;)
96
+ {
97
+ digitalWrite (LED_PIN, !digitalRead (LED_PIN));
98
+ delay (100 );
99
+ }
100
+ }
101
+
102
+ void timer_callback (rcl_timer_t * timer, int64_t last_call_time)
103
+ {
104
+ RCLC_UNUSED (last_call_time);
105
+ if (timer != NULL )
106
+ {
107
+ RCSOFTCHECK (rcl_publish (&publisher, &msg, NULL ));
108
+ msg.data ++;
109
+ }
110
+ }
0 commit comments