@@ -75,6 +75,11 @@ int main(int argc, char ** argv)
7575
7676 const char * mode = argv [1 ];
7777
78+ // Init data
79+ msg .data .data = "This is a message sent after pinging micro-ROS Agent" ;
80+ msg .data .size = strlen (msg .data .data );
81+ msg .data .capacity = msg .data .size + 1 ;
82+
7883 /**
7984 * Basic mode
8085 */
@@ -134,22 +139,15 @@ int main(int argc, char ** argv)
134139 RCCHECK (rclc_executor_init (& executor , & support .context , 1 , & allocator ));
135140 RCCHECK (rclc_executor_add_timer (& executor , & timer ));
136141
137- // Init data
138- (void ) rosidl_runtime_c__String__init (& msg .data );
139- (void ) rosidl_runtime_c__String__assign (
140- & msg .data ,
141- "This is a message sent after pinging micro-ROS Agent" );
142-
143142 // Spin executor
144143 rclc_executor_spin (& executor );
145144
146- // Free micro-ROS resources before exiting
147- (void ) rosidl_runtime_c__String__fini (& msg .data );
145+ (void )! rcl_publisher_fini (& publisher , & node );
146+ (void )! rcl_timer_fini (& timer );
147+ (void )! rclc_executor_fini (& executor );
148+ (void )! rcl_node_fini (& node );
149+ (void )! rclc_support_fini (& support );
148150
149- RCCHECK (rclc_executor_fini (& executor ));
150- RCCHECK (rcl_publisher_fini (& publisher , & node ));
151- RCCHECK (rcl_node_fini (& node ));
152- RCCHECK (rclc_support_fini (& support ));
153151 } else {
154152 return usage ();
155153 }
0 commit comments