1+ #include <rclc/rclc.h>
2+ #include <std_msgs/msg/string.h>
3+ #include <std_msgs/msg/float64.h>
4+ #include <std_msgs/msg/int32.h>
5+ #include <std_msgs/msg/u_int32.h>
6+
7+ #include <stdio.h>
8+
9+ #define ASSERT (ptr ) if (ptr == NULL) return -1;
10+
11+ static float altitude ;
12+ static uint32_t engine_power ;
13+ static unsigned it ;
14+ static char Alert [200 ];
15+
16+ /**
17+ * @brief Update screen
18+ *
19+ */
20+ void UpdateDisplay ()
21+ {
22+ printf ("\r[received messages: %7u] [Altitude: %8.2f] [Engine power: %8u] [Status: %10s]" , it ++ , altitude , engine_power , Alert );
23+ }
24+
25+
26+ /**
27+ * @brief new alert callback
28+ *
29+ * @param msgin
30+ */
31+ void on_alert_message (const void * msgin )
32+ {
33+ const std_msgs__msg__String * msg = (const std_msgs__msg__String * )msgin ;
34+ strcpy (Alert , msg -> data .data );
35+
36+ UpdateDisplay ();
37+ }
38+
39+
40+ /**
41+ * @brief new altitude calback
42+ *
43+ * @param msgin
44+ */
45+ void on_altitude_message (const void * msgin )
46+ {
47+ std_msgs__msg__Float64 * msg = (std_msgs__msg__Float64 * )msgin ;
48+
49+ altitude = msg -> data ;
50+ UpdateDisplay ();
51+ }
52+
53+ /**
54+ * @brief
55+ *
56+ * @param msgin
57+ */
58+ void on_power_message (const void * msgin )
59+ {
60+ std_msgs__msg__UInt32 * msg = (std_msgs__msg__UInt32 * )msgin ;
61+
62+ engine_power = msg -> data ;
63+ UpdateDisplay ();
64+ }
65+
66+
67+ /**
68+ * @brief Main
69+ *
70+ * @param argc
71+ * @param argv
72+ * @return int
73+ */
74+ int main (int argc , char * argv [])
75+ {
76+ (void )argc ;
77+ (void )argv ;
78+
79+ rclc_node_t * node = NULL ;
80+ rclc_subscription_t * alert_subscription = NULL ;
81+ rclc_subscription_t * altitude_subscription = NULL ;
82+ rclc_subscription_t * power_subscription = NULL ;
83+
84+
85+ rclc_init (0 , NULL );
86+
87+ node = rclc_create_node ("rad0_display_c" , "" );
88+ ASSERT (node );
89+ alert_subscription = rclc_create_subscription (node , RCLC_GET_MSG_TYPE_SUPPORT (std_msgs , msg , String ), "std_msgs_msg_String" , on_alert_message , 1 , false);
90+ ASSERT (alert_subscription );
91+ altitude_subscription = rclc_create_subscription (node , RCLC_GET_MSG_TYPE_SUPPORT (std_msgs , msg , Float64 ), "std_msgs_msg_Float64" , on_altitude_message , 1 , false);
92+ ASSERT (altitude_subscription );
93+ power_subscription = rclc_create_subscription (node , RCLC_GET_MSG_TYPE_SUPPORT (std_msgs , msg , UInt32 ), "std_msgs_msg_UInt32" , on_power_message , 1 , false);
94+ ASSERT (power_subscription );
95+
96+ rclc_spin_node (node );
97+
98+ if (alert_subscription ) rclc_destroy_subscription (alert_subscription );
99+ if (altitude_subscription ) rclc_destroy_subscription (altitude_subscription );
100+ if (node ) rclc_destroy_node (node );
101+
102+ printf ("Display node closed." );
103+
104+ }
0 commit comments