|
23 | 23 |
|
24 | 24 | #include "subscribe_array_types.hpp" |
25 | 25 | #include "subscribe_basic_types.hpp" |
| 26 | +#include "subscribe_key_types.hpp" |
26 | 27 | #include "subscribe_string_types.hpp" |
27 | 28 |
|
28 | 29 | int main(int argc, char ** argv) |
@@ -53,6 +54,7 @@ int main(int argc, char ** argv) |
53 | 54 | auto messages_defaults = get_messages_defaults(); |
54 | 55 | auto messages_strings = get_messages_strings(); |
55 | 56 | auto messages_wstrings = get_messages_wstrings(); |
| 57 | + auto messages_keyed_string = get_messages_keyed_string(); |
56 | 58 |
|
57 | 59 | rclcpp::SubscriptionBase::SharedPtr subscriber; |
58 | 60 | std::vector<bool> received_messages; // collect flags about received messages |
@@ -85,6 +87,8 @@ int main(int argc, char ** argv) |
85 | 87 | subscriber = subscribe_strings(node, message, messages_strings, received_messages); |
86 | 88 | } else if (message == "WStrings") { |
87 | 89 | subscriber = subscribe_wstrings(node, message, messages_wstrings, received_messages); |
| 90 | + } else if (message == "KeyedString") { |
| 91 | + subscriber = subscribe_keyed_string(node, message, messages_keyed_string, received_messages); |
88 | 92 | } else { |
89 | 93 | fprintf(stderr, "Unknown message argument '%s'\n", message.c_str()); |
90 | 94 | rclcpp::shutdown(); |
|
0 commit comments