Skip to content

Commit c976fe0

Browse files
committed
Added support for KeyedString.
Signed-off-by: Miguel Company <[email protected]>
1 parent b79c0ee commit c976fe0

File tree

6 files changed

+74
-0
lines changed

6 files changed

+74
-0
lines changed

test_communication/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -397,6 +397,7 @@ if(BUILD_TESTING)
397397
add_library(subscribe_types STATIC
398398
"test/subscribe_array_types.cpp"
399399
"test/subscribe_basic_types.cpp"
400+
"test/subscribe_key_types.cpp"
400401
"test/subscribe_string_types.cpp")
401402
target_link_libraries(subscribe_types
402403
rclcpp::rclcpp
Lines changed: 32 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
// Copyright 2015 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include <string>
16+
#include <vector>
17+
18+
#include "rclcpp/rclcpp.hpp"
19+
#include "test_msgs/msg/keyed_string.hpp"
20+
21+
#include "subscribe_helper.hpp"
22+
#include "subscribe_key_types.hpp"
23+
24+
rclcpp::SubscriptionBase::SharedPtr subscribe_keyed_string(
25+
rclcpp::Node::SharedPtr node,
26+
const std::string & message_type,
27+
const std::vector<test_msgs::msg::KeyedString::SharedPtr> & expected_messages,
28+
std::vector<bool> & received_messages)
29+
{
30+
return subscribe<test_msgs::msg::KeyedString>(
31+
node, message_type, expected_messages, received_messages);
32+
}
Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
// Copyright 2015 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef SUBSCRIBE_KEY_TYPES_HPP_
16+
#define SUBSCRIBE_KEY_TYPES_HPP_
17+
18+
#include <string>
19+
#include <vector>
20+
21+
#include "rclcpp/rclcpp.hpp"
22+
#include "test_msgs/msg/keyed_string.hpp"
23+
24+
rclcpp::SubscriptionBase::SharedPtr subscribe_keyed_string(
25+
rclcpp::Node::SharedPtr node,
26+
const std::string & message_type,
27+
const std::vector<test_msgs::msg::KeyedString::SharedPtr> & expected_messages,
28+
std::vector<bool> & received_messages);
29+
30+
#endif // SUBSCRIBE_KEY_TYPES_HPP_

test_communication/test/test_publisher.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -107,6 +107,8 @@ int main(int argc, char ** argv)
107107
publish<test_msgs::msg::Strings>(node, message, get_messages_strings());
108108
} else if (message == "WStrings") {
109109
publish<test_msgs::msg::WStrings>(node, message, get_messages_wstrings());
110+
} else if (message == "KeyedString") {
111+
publish<test_msgs::msg::KeyedString>(node, message, get_messages_keyed_string());
110112
} else {
111113
fprintf(stderr, "Unknown message argument '%s'\n", message.c_str());
112114
rclcpp::shutdown();

test_communication/test/test_publisher_subscriber.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525

2626
#include "subscribe_array_types.hpp"
2727
#include "subscribe_basic_types.hpp"
28+
#include "subscribe_key_types.hpp"
2829
#include "subscribe_string_types.hpp"
2930

3031
template<typename T>
@@ -98,6 +99,7 @@ int main(int argc, char ** argv)
9899
auto messages_defaults = get_messages_defaults();
99100
auto messages_strings = get_messages_strings();
100101
auto messages_wstrings = get_messages_wstrings();
102+
auto messages_keyed_string = get_messages_keyed_string();
101103

102104
std::thread spin_thread([node]() {
103105
rclcpp::spin(node);
@@ -148,6 +150,9 @@ int main(int argc, char ** argv)
148150
} else if (message == "WStrings") {
149151
subscriber = subscribe_wstrings(node, message, messages_wstrings, received_messages);
150152
publish<test_msgs::msg::WStrings>(node, message, messages_wstrings);
153+
} else if (message == "KeyedString") {
154+
subscriber = subscribe_keyed_string(node, message, messages_keyed_string, received_messages);
155+
publish<test_msgs::msg::KeyedString>(node, message, messages_keyed_string);
151156
} else {
152157
fprintf(stderr, "Unknown message argument '%s'\n", message.c_str());
153158
return 1;

test_communication/test/test_subscriber.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323

2424
#include "subscribe_array_types.hpp"
2525
#include "subscribe_basic_types.hpp"
26+
#include "subscribe_key_types.hpp"
2627
#include "subscribe_string_types.hpp"
2728

2829
int main(int argc, char ** argv)
@@ -53,6 +54,7 @@ int main(int argc, char ** argv)
5354
auto messages_defaults = get_messages_defaults();
5455
auto messages_strings = get_messages_strings();
5556
auto messages_wstrings = get_messages_wstrings();
57+
auto messages_keyed_string = get_messages_keyed_string();
5658

5759
rclcpp::SubscriptionBase::SharedPtr subscriber;
5860
std::vector<bool> received_messages; // collect flags about received messages
@@ -85,6 +87,8 @@ int main(int argc, char ** argv)
8587
subscriber = subscribe_strings(node, message, messages_strings, received_messages);
8688
} else if (message == "WStrings") {
8789
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);
8892
} else {
8993
fprintf(stderr, "Unknown message argument '%s'\n", message.c_str());
9094
rclcpp::shutdown();

0 commit comments

Comments
 (0)