Skip to content

Commit b8ce03d

Browse files
Update reconnection example (#913) (#916)
* Update reconnection example Signed-off-by: Pablo Garrido <[email protected]> * FIx indentation Signed-off-by: Pablo Garrido <[email protected]> * Typo Signed-off-by: Pablo Garrido <[email protected]> * Typo Signed-off-by: Pablo Garrido <[email protected]> * Typo Signed-off-by: Pablo Garrido <[email protected]> (cherry picked from commit 561c615) Co-authored-by: Pablo Garrido <[email protected]>
1 parent a21ff40 commit b8ce03d

File tree

1 file changed

+86
-61
lines changed

1 file changed

+86
-61
lines changed

examples/micro-ros_reconnection_example/micro-ros_reconnection_example.ino

Lines changed: 86 additions & 61 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,11 @@
1111

1212
#define LED_PIN 13
1313
#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){return false;}}
14+
#define EXECUTE_EVERY_N_MS(MS, X) do { \
15+
static volatile int64_t init = -1; \
16+
if (init == -1) { init = uxr_millis();} \
17+
if (uxr_millis() - init > MS) { X; init = uxr_millis();} \
18+
} while (0)\
1419

1520
rclc_support_t support;
1621
rcl_node_t node;
@@ -21,89 +26,109 @@ rcl_publisher_t publisher;
2126
std_msgs__msg__Int32 msg;
2227
bool micro_ros_init_successful;
2328

29+
enum states {
30+
WAITING_AGENT,
31+
AGENT_AVAILABLE,
32+
AGENT_CONNECTED,
33+
AGENT_DISCONNECTED
34+
} state;
35+
2436
void timer_callback(rcl_timer_t * timer, int64_t last_call_time)
2537
{
26-
(void) last_call_time;
27-
if (timer != NULL) {
28-
rcl_publish(&publisher, &msg, NULL);
29-
msg.data++;
30-
}
38+
(void) last_call_time;
39+
if (timer != NULL) {
40+
rcl_publish(&publisher, &msg, NULL);
41+
msg.data++;
42+
}
3143
}
3244

3345
// Functions create_entities and destroy_entities can take several seconds.
34-
// In order to reduce this rebuild the library with
46+
// In order to reduce this rebuild the library with
3547
// - RMW_UXRCE_ENTITY_CREATION_DESTROY_TIMEOUT=0
3648
// - UCLIENT_MAX_SESSION_CONNECTION_ATTEMPTS=3
3749

3850
bool create_entities()
39-
{
40-
allocator = rcl_get_default_allocator();
41-
42-
// create init_options
43-
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
44-
45-
// create node
46-
RCCHECK(rclc_node_init_default(&node, "int32_publisher_rclc", "", &support));
47-
48-
// create publisher
49-
RCCHECK(rclc_publisher_init_best_effort(
50-
&publisher,
51-
&node,
52-
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
53-
"std_msgs_msg_Int32"));
54-
55-
// create timer,
56-
const unsigned int timer_timeout = 1000;
57-
RCCHECK(rclc_timer_init_default(
58-
&timer,
59-
&support,
60-
RCL_MS_TO_NS(timer_timeout),
61-
timer_callback));
62-
63-
// create executor
64-
executor = rclc_executor_get_zero_initialized_executor();
65-
RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
66-
RCCHECK(rclc_executor_add_timer(&executor, &timer));
67-
68-
micro_ros_init_successful = true;
51+
{
52+
allocator = rcl_get_default_allocator();
53+
54+
// create init_options
55+
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
56+
57+
// create node
58+
RCCHECK(rclc_node_init_default(&node, "int32_publisher_rclc", "", &support));
59+
60+
// create publisher
61+
RCCHECK(rclc_publisher_init_best_effort(
62+
&publisher,
63+
&node,
64+
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
65+
"std_msgs_msg_Int32"));
66+
67+
// create timer,
68+
const unsigned int timer_timeout = 1000;
69+
RCCHECK(rclc_timer_init_default(
70+
&timer,
71+
&support,
72+
RCL_MS_TO_NS(timer_timeout),
73+
timer_callback));
74+
75+
// create executor
76+
executor = rclc_executor_get_zero_initialized_executor();
77+
RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
78+
RCCHECK(rclc_executor_add_timer(&executor, &timer));
79+
80+
return true;
6981
}
7082

7183
void destroy_entities()
7284
{
73-
rcl_publisher_fini(&publisher, &node);
74-
rcl_node_fini(&node);
75-
rcl_timer_fini(&timer);
76-
rclc_executor_fini(&executor);
77-
rclc_support_fini(&support);
78-
79-
micro_ros_init_successful = false;
85+
rmw_context_t * rmw_context = rcl_context_get_rmw_context(&support.context);
86+
(void) rmw_uros_set_context_entity_destroy_session_timeout(rmw_context, 0);
87+
88+
rcl_publisher_fini(&publisher, &node);
89+
rcl_timer_fini(&timer);
90+
rclc_executor_fini(&executor);
91+
rcl_node_fini(&node);
92+
rclc_support_fini(&support);
8093
}
8194

8295
void setup() {
83-
set_microros_transports();
96+
set_microros_transports();
8497
pinMode(LED_PIN, OUTPUT);
85-
digitalWrite(LED_PIN, HIGH);
8698

87-
micro_ros_init_successful = false;
99+
state = WAITING_AGENT;
100+
88101
msg.data = 0;
89102
}
90103

91104
void loop() {
92-
uint32_t delay = 100000;
93-
if (RMW_RET_OK == rmw_uros_ping_agent(50, 2))
94-
{
95-
delay = 500000;
96-
if (!micro_ros_init_successful) {
97-
create_entities();
98-
} else {
99-
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(10));
100-
}
101-
}
102-
else if (micro_ros_init_successful)
103-
{
104-
destroy_entities();
105+
switch (state) {
106+
case WAITING_AGENT:
107+
EXECUTE_EVERY_N_MS(500, state = (RMW_RET_OK == rmw_uros_ping_agent(100, 1)) ? AGENT_AVAILABLE : WAITING_AGENT;);
108+
break;
109+
case AGENT_AVAILABLE:
110+
state = (true == create_entities()) ? AGENT_CONNECTED : WAITING_AGENT;
111+
if (state == WAITING_AGENT) {
112+
destroy_entities();
113+
};
114+
break;
115+
case AGENT_CONNECTED:
116+
EXECUTE_EVERY_N_MS(200, state = (RMW_RET_OK == rmw_uros_ping_agent(100, 1)) ? AGENT_CONNECTED : AGENT_DISCONNECTED;);
117+
if (state == AGENT_CONNECTED) {
118+
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
119+
}
120+
break;
121+
case AGENT_DISCONNECTED:
122+
destroy_entities();
123+
state = WAITING_AGENT;
124+
break;
125+
default:
126+
break;
105127
}
106128

107-
digitalWrite(LED_PIN, !digitalRead(LED_PIN));
108-
delayMicroseconds(delay);
129+
if (state == AGENT_CONNECTED) {
130+
digitalWrite(LED_PIN, 1);
131+
} else {
132+
digitalWrite(LED_PIN, 0);
133+
}
109134
}

0 commit comments

Comments
 (0)