Skip to content

Commit fa0c0e3

Browse files
authored
Add type adaption example (#300)
* Add type masquerading examples Signed-off-by: Audrow Nash <[email protected]> * Update examples Signed-off-by: Audrow Nash <[email protected]> * Apply feedback Signed-off-by: Audrow Nash <[email protected]> * Update publisher's comment Signed-off-by: Audrow Nash <[email protected]>
1 parent 1e8401d commit fa0c0e3

File tree

4 files changed

+188
-0
lines changed

4 files changed

+188
-0
lines changed

rclcpp/topics/minimal_publisher/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,9 @@ ament_target_dependencies(publisher_lambda rclcpp std_msgs)
2020
add_executable(publisher_member_function member_function.cpp)
2121
ament_target_dependencies(publisher_member_function rclcpp std_msgs)
2222

23+
add_executable(publisher_member_function_with_type_adapter member_function_with_type_adapter.cpp)
24+
ament_target_dependencies(publisher_member_function_with_type_adapter rclcpp std_msgs)
25+
2326
add_executable(publisher_member_function_with_unique_network_flow_endpoints member_function_with_unique_network_flow_endpoints.cpp)
2427
ament_target_dependencies(publisher_member_function_with_unique_network_flow_endpoints rclcpp std_msgs)
2528

@@ -29,6 +32,7 @@ ament_target_dependencies(publisher_not_composable rclcpp std_msgs)
2932
install(TARGETS
3033
publisher_lambda
3134
publisher_member_function
35+
publisher_member_function_with_type_adapter
3236
publisher_member_function_with_unique_network_flow_endpoints
3337
publisher_not_composable
3438
DESTINATION lib/${PROJECT_NAME}
Lines changed: 94 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,94 @@
1+
// Copyright 2021 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 <chrono>
16+
#include <functional>
17+
#include <memory>
18+
#include <string>
19+
20+
#include "rclcpp/type_adapter.hpp"
21+
#include "rclcpp/rclcpp.hpp"
22+
23+
#include "std_msgs/msg/string.hpp"
24+
25+
using namespace std::chrono_literals;
26+
27+
/* Normally a TypeAdapter specialization like this would go in a header
28+
* and be reused by the publisher and subscriber rather than copy-pasted
29+
* like this. We chose to include this here because it makes this example
30+
* more "self-contained". */
31+
32+
template<>
33+
struct rclcpp::TypeAdapter<std::string, std_msgs::msg::String>
34+
{
35+
using is_specialized = std::true_type;
36+
using custom_type = std::string;
37+
using ros_message_type = std_msgs::msg::String;
38+
39+
static
40+
void
41+
convert_to_ros_message(
42+
const custom_type & source,
43+
ros_message_type & destination)
44+
{
45+
destination.data = source;
46+
}
47+
48+
static
49+
void
50+
convert_to_custom(
51+
const ros_message_type & source,
52+
custom_type & destination)
53+
{
54+
destination = source.data;
55+
}
56+
};
57+
58+
/* In this example, a publisher uses a type adapter to use a `std::string`
59+
* in place of a `std_msgs::msg::String` in the argument expected by
60+
* the publish method. Note that publish will also work with a
61+
* `std_msgs::msg::String` argument. */
62+
63+
class MinimalPublisher : public rclcpp::Node
64+
{
65+
using MyAdaptedType = rclcpp::TypeAdapter<std::string, std_msgs::msg::String>;
66+
67+
public:
68+
MinimalPublisher()
69+
: Node("minimal_publisher"), count_(0)
70+
{
71+
publisher_ = this->create_publisher<MyAdaptedType>("topic", 10);
72+
timer_ = this->create_wall_timer(
73+
500ms, std::bind(&MinimalPublisher::timer_callback, this));
74+
}
75+
76+
private:
77+
void timer_callback()
78+
{
79+
std::string message = "Hello, world! " + std::to_string(count_++);
80+
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.c_str());
81+
publisher_->publish(message);
82+
}
83+
rclcpp::TimerBase::SharedPtr timer_;
84+
rclcpp::Publisher<MyAdaptedType>::SharedPtr publisher_;
85+
size_t count_;
86+
};
87+
88+
int main(int argc, char * argv[])
89+
{
90+
rclcpp::init(argc, argv);
91+
rclcpp::spin(std::make_shared<MinimalPublisher>());
92+
rclcpp::shutdown();
93+
return 0;
94+
}

rclcpp/topics/minimal_subscriber/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,9 @@ ament_target_dependencies(subscriber_member_function rclcpp std_msgs)
2323
add_executable(subscriber_member_function_with_topic_statistics member_function_with_topic_statistics.cpp)
2424
ament_target_dependencies(subscriber_member_function_with_topic_statistics rclcpp std_msgs)
2525

26+
add_executable(subscriber_member_function_with_type_adapter member_function_with_type_adapter.cpp)
27+
ament_target_dependencies(subscriber_member_function_with_type_adapter rclcpp std_msgs)
28+
2629
add_executable(subscriber_member_function_with_unique_network_flow_endpoints member_function_with_unique_network_flow_endpoints.cpp)
2730
ament_target_dependencies(subscriber_member_function_with_unique_network_flow_endpoints rclcpp std_msgs)
2831

@@ -33,6 +36,7 @@ install(TARGETS
3336
subscriber_lambda
3437
subscriber_member_function
3538
subscriber_member_function_with_topic_statistics
39+
subscriber_member_function_with_type_adapter
3640
subscriber_member_function_with_unique_network_flow_endpoints
3741
subscriber_not_composable
3842
DESTINATION lib/${PROJECT_NAME})
Lines changed: 86 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,86 @@
1+
// Copyright 2021 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 <functional>
16+
#include <memory>
17+
#include <string>
18+
19+
#include "rclcpp/type_adapter.hpp"
20+
#include "rclcpp/rclcpp.hpp"
21+
22+
#include "std_msgs/msg/string.hpp"
23+
24+
using std::placeholders::_1;
25+
26+
/* Normally a TypeAdapter specialization like this would go in a header
27+
* and be reused by the publisher and subscriber rather than copy-pasted
28+
* like this. We chose to include this here because it makes this example
29+
* more "self-contained". */
30+
31+
template<>
32+
struct rclcpp::TypeAdapter<std::string, std_msgs::msg::String>
33+
{
34+
using is_specialized = std::true_type;
35+
using custom_type = std::string;
36+
using ros_message_type = std_msgs::msg::String;
37+
38+
static
39+
void
40+
convert_to_ros_message(
41+
const custom_type & source,
42+
ros_message_type & destination)
43+
{
44+
destination.data = source;
45+
}
46+
47+
static
48+
void
49+
convert_to_custom(
50+
const ros_message_type & source,
51+
custom_type & destination)
52+
{
53+
destination = source.data;
54+
}
55+
};
56+
57+
/* In this example, a subscriber uses a type adapter to use a `std::string`
58+
* in place of a `std_msgs::msg::String` in the subscription's callback. */
59+
60+
class MinimalSubscriber : public rclcpp::Node
61+
{
62+
using MyAdaptedType = rclcpp::TypeAdapter<std::string, std_msgs::msg::String>;
63+
64+
public:
65+
MinimalSubscriber()
66+
: Node("minimal_subscriber")
67+
{
68+
subscription_ = this->create_subscription<MyAdaptedType>(
69+
"topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
70+
}
71+
72+
private:
73+
void topic_callback(const std::string & msg) const
74+
{
75+
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.c_str());
76+
}
77+
rclcpp::Subscription<MyAdaptedType>::SharedPtr subscription_;
78+
};
79+
80+
int main(int argc, char * argv[])
81+
{
82+
rclcpp::init(argc, argv);
83+
rclcpp::spin(std::make_shared<MinimalSubscriber>());
84+
rclcpp::shutdown();
85+
return 0;
86+
}

0 commit comments

Comments
 (0)