Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Changes to allow improved template logic when creating publishers and subscribers #33

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 9 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,20 +12,20 @@ This project provides the ability to publish and subscribe with Protobuf Datatyp
```
#### Publisher Example
```cpp
publisher_ = this->create_publisher<std_msgs::msg::typesupport_protobuf_cpp::StringTypeAdapter>("topic", 10);
publisher_ = this->create_publisher<std_msgs::msg::pb::String>("topic", 10);
```
To publish a message, it is only required to specify the adapter type to send the topic.
To publish a message, it is only required to specify the protobuf message type to send the topic.

#### Subscriber Example
```cpp
subscription2_ = this->create_subscription<std_msgs::msg::typesupport_protobuf_cpp::StringTypeAdapter>(
subscription2_ = this->create_subscription<std_msgs::msg::pb::String>(
"topic", 10, std::bind(&MinimalSubscriber::topic_callback2, this, _1));
void topic_callback2(const std_msgs::msg::pb::String & msg) const
{
RCLCPP_INFO(this->get_logger(), "I heard Proto: '%s'", msg.data().c_str());
}
```
To subscribe to the topic the user needs to specify the adapter type, and for the callback specify the protobuf message to hear the message received.
To subscribe to the topic the user needs to specify the protobuf message type, and for the callback specify the protobuf message to hear the message received.

Another path to hear the message is using the ROS types messages:

Expand Down Expand Up @@ -60,6 +60,9 @@ To adapt the prototype message to a ROS type, protobuf type support generates a
* static void convert_to_ros_message(const custom_type &, ros_message_type &),
* static void convert_to_custom(const ros_message_type &, custom_type &)

The adapted type is also registered as the default type adapter for the ros type:

* RCLCPP_USING_CUSTOM_TYPE_AS_ROS_MESSAGE_TYPE( /* proto_type */, /* ros_type */ ));

The convert function must convert from one type to the other, see [Type Adaptation Feature](https://ros.org/reps/rep-2007.html) for more information.

Expand Down Expand Up @@ -94,6 +97,8 @@ template<>
}
};


RCLCPP_USING_CUSTOM_TYPE_AS_ROS_MESSAGE_TYPE(::std_msgs::msg::pb::String, ::std_msgs::msg::String));
```

#### Mapping from IDL -> Protobuf Type:
Expand Down
12 changes: 6 additions & 6 deletions rosidl_typeadapter_protobuf_test/test/subscribe_array_types.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ rclcpp::SubscriptionBase::SharedPtr subscribe_arrays(
const std::vector<std::shared_ptr<test_msgs::msg::pb::Arrays>> & expected_messages,
std::vector<bool> & received_messages)
{
return subscribe<test_msgs::msg::typesupport_protobuf_cpp::ArraysTypeAdapter>(
return subscribe<test_msgs::msg::pb::Arrays>(
node, message_type, expected_messages, received_messages);
}

Expand All @@ -47,7 +47,7 @@ rclcpp::SubscriptionBase::SharedPtr subscribe_unbounded_sequences(
const std::vector<std::shared_ptr<test_msgs::msg::pb::UnboundedSequences>> & expected_messages,
std::vector<bool> & received_messages)
{
return subscribe<test_msgs::msg::typesupport_protobuf_cpp::UnboundedSequencesTypeAdapter>(
return subscribe<test_msgs::msg::pb::UnboundedSequences>(
node, message_type, expected_messages, received_messages);
}

Expand All @@ -57,7 +57,7 @@ rclcpp::SubscriptionBase::SharedPtr subscribe_bounded_plain_sequences(
const std::vector<std::shared_ptr<test_msgs::msg::pb::BoundedPlainSequences>> & expected_messages,
std::vector<bool> & received_messages)
{
return subscribe<test_msgs::msg::typesupport_protobuf_cpp::BoundedPlainSequencesTypeAdapter>(
return subscribe<test_msgs::msg::pb::BoundedPlainSequences>(
node, message_type, expected_messages, received_messages);
}

Expand All @@ -67,7 +67,7 @@ rclcpp::SubscriptionBase::SharedPtr subscribe_bounded_sequences(
const std::vector<std::shared_ptr<test_msgs::msg::pb::BoundedSequences>> & expected_messages,
std::vector<bool> & received_messages)
{
return subscribe<test_msgs::msg::typesupport_protobuf_cpp::BoundedSequencesTypeAdapter>(
return subscribe<test_msgs::msg::pb::BoundedSequences>(
node, message_type, expected_messages, received_messages);
}

Expand All @@ -77,7 +77,7 @@ rclcpp::SubscriptionBase::SharedPtr subscribe_multi_nested(
const std::vector<std::shared_ptr<test_msgs::msg::pb::MultiNested>> & expected_messages,
std::vector<bool> & received_messages)
{
return subscribe<test_msgs::msg::typesupport_protobuf_cpp::MultiNestedTypeAdapter>(
return subscribe<test_msgs::msg::pb::MultiNested>(
node, message_type, expected_messages, received_messages);
}

Expand All @@ -87,6 +87,6 @@ rclcpp::SubscriptionBase::SharedPtr subscribe_nested(
const std::vector<std::shared_ptr<test_msgs::msg::pb::Nested>> & expected_messages,
std::vector<bool> & received_messages)
{
return subscribe<test_msgs::msg::typesupport_protobuf_cpp::NestedTypeAdapter>(
return subscribe<test_msgs::msg::pb::Nested>(
node, message_type, expected_messages, received_messages);
}
10 changes: 5 additions & 5 deletions rosidl_typeadapter_protobuf_test/test/subscribe_basic_types.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ rclcpp::SubscriptionBase::SharedPtr subscribe_empty(
const std::vector<std::shared_ptr<test_msgs::msg::pb::Empty>> & messages_expected,
std::vector<bool> & received_messages)
{
return subscribe<test_msgs::msg::typesupport_protobuf_cpp::EmptyTypeAdapter>(
return subscribe<test_msgs::msg::pb::Empty>(
node, message_type, messages_expected, received_messages);
}

Expand All @@ -45,7 +45,7 @@ rclcpp::SubscriptionBase::SharedPtr subscribe_basic_types(
const std::vector<std::shared_ptr<test_msgs::msg::pb::BasicTypes>> & messages_expected,
std::vector<bool> & received_messages)
{
return subscribe<test_msgs::msg::typesupport_protobuf_cpp::BasicTypesTypeAdapter>(
return subscribe<test_msgs::msg::pb::BasicTypes>(
node, message_type, messages_expected, received_messages);
}

Expand All @@ -55,7 +55,7 @@ rclcpp::SubscriptionBase::SharedPtr subscribe_builtins(
const std::vector<std::shared_ptr<test_msgs::msg::pb::Builtins>> & messages_expected,
std::vector<bool> & received_messages)
{
return subscribe<test_msgs::msg::typesupport_protobuf_cpp::BuiltinsTypeAdapter>(
return subscribe<test_msgs::msg::pb::Builtins>(
node, message_type, messages_expected, received_messages);
}

Expand All @@ -65,7 +65,7 @@ rclcpp::SubscriptionBase::SharedPtr subscribe_constants(
const std::vector<std::shared_ptr<test_msgs::msg::pb::Constants>> & messages_expected,
std::vector<bool> & received_messages)
{
return subscribe<test_msgs::msg::typesupport_protobuf_cpp::ConstantsTypeAdapter>(
return subscribe<test_msgs::msg::pb::Constants>(
node, message_type, messages_expected, received_messages);
}

Expand All @@ -75,6 +75,6 @@ rclcpp::SubscriptionBase::SharedPtr subscribe_defaults(
const std::vector<std::shared_ptr<test_msgs::msg::pb::Defaults>> & messages_expected,
std::vector<bool> & received_messages)
{
return subscribe<test_msgs::msg::typesupport_protobuf_cpp::DefaultsTypeAdapter>(
return subscribe<test_msgs::msg::pb::Defaults>(
node, message_type, messages_expected, received_messages);
}
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ rclcpp::SubscriptionBase::SharedPtr subscribe_strings(
const std::vector<std::shared_ptr<test_msgs::msg::pb::Strings>> & expected_messages,
std::vector<bool> & received_messages)
{
return subscribe<test_msgs::msg::typesupport_protobuf_cpp::StringsTypeAdapter>(
return subscribe<test_msgs::msg::pb::Strings>(
node, message_type, expected_messages, received_messages);
}

Expand All @@ -43,6 +43,6 @@ rclcpp::SubscriptionBase::SharedPtr subscribe_wstrings(
const std::vector<std::shared_ptr<test_msgs::msg::pb::WStrings>> & expected_messages,
std::vector<bool> & received_messages)
{
return subscribe<test_msgs::msg::typesupport_protobuf_cpp::WStringsTypeAdapter>(
return subscribe<test_msgs::msg::pb::WStrings>(
node, message_type, expected_messages, received_messages);
}
26 changes: 13 additions & 13 deletions rosidl_typeadapter_protobuf_test/test/test_proto_typeadapt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,58 +108,58 @@ int main(int argc, char ** argv)

if (message == "Empty") {
subscriber = subscribe_empty(node, message, messages_empty, received_messages);
publish<test_msgs::msg::typesupport_protobuf_cpp::EmptyTypeAdapter>(
publish<test_msgs::msg::pb::Empty>(
node, message, messages_empty);
} else if (message == "BasicTypes") {
subscriber = subscribe_basic_types(node, message, messages_basic_types, received_messages);
publish<test_msgs::msg::typesupport_protobuf_cpp::BasicTypesTypeAdapter>(
publish<test_msgs::msg::pb::BasicTypes>(
node, message, messages_basic_types);
} else if (message == "Arrays") {
subscriber = subscribe_arrays(node, message, messages_arrays, received_messages);
publish<test_msgs::msg::typesupport_protobuf_cpp::ArraysTypeAdapter>(
publish<test_msgs::msg::pb::Arrays>(
node, message, messages_arrays);
} else if (message == "UnboundedSequences") {
subscriber = subscribe_unbounded_sequences(
node, message, messages_unbounded_sequences, received_messages);
publish<test_msgs::msg::typesupport_protobuf_cpp::UnboundedSequencesTypeAdapter>(
publish<test_msgs::msg::pb::UnboundedSequences>(
node, message, messages_unbounded_sequences);
} else if (message == "BoundedPlainSequences") {
subscriber = subscribe_bounded_plain_sequences(
node, message, messages_bounded_plain_sequences, received_messages);
publish<test_msgs::msg::typesupport_protobuf_cpp::BoundedPlainSequencesTypeAdapter>(
publish<test_msgs::msg::pb::BoundedPlainSequences>(
node, message, messages_bounded_plain_sequences);
} else if (message == "BoundedSequences") {
subscriber = subscribe_bounded_sequences(
node, message, messages_bounded_sequences, received_messages);
publish<test_msgs::msg::typesupport_protobuf_cpp::BoundedSequencesTypeAdapter>(
publish<test_msgs::msg::pb::BoundedSequences>(
node, message, messages_bounded_sequences);
} else if (message == "MultiNested") {
subscriber = subscribe_multi_nested(node, message, messages_multi_nested, received_messages);
publish<test_msgs::msg::typesupport_protobuf_cpp::MultiNestedTypeAdapter>(
publish<test_msgs::msg::pb::MultiNested>(
node, message, messages_multi_nested);
} else if (message == "Nested") {
subscriber = subscribe_nested(node, message, messages_nested, received_messages);
publish<test_msgs::msg::typesupport_protobuf_cpp::NestedTypeAdapter>(
publish<test_msgs::msg::pb::Nested>(
node, message, messages_nested);
} else if (message == "Builtins") {
subscriber = subscribe_builtins(node, message, messages_builtins, received_messages);
publish<test_msgs::msg::typesupport_protobuf_cpp::BuiltinsTypeAdapter>(
publish<test_msgs::msg::pb::Builtins>(
node, message, messages_builtins);
} else if (message == "Constants") {
subscriber = subscribe_constants(node, message, messages_constants, received_messages);
publish<test_msgs::msg::typesupport_protobuf_cpp::ConstantsTypeAdapter>(
publish<test_msgs::msg::pb::Constants>(
node, message, messages_constants);
} else if (message == "Defaults") {
subscriber = subscribe_defaults(node, message, messages_defaults, received_messages);
publish<test_msgs::msg::typesupport_protobuf_cpp::DefaultsTypeAdapter>(
publish<test_msgs::msg::pb::Defaults>(
node, message, messages_defaults);
} else if (message == "Strings") {
subscriber = subscribe_strings(node, message, messages_strings, received_messages);
publish<test_msgs::msg::typesupport_protobuf_cpp::StringsTypeAdapter>(
publish<test_msgs::msg::pb::Strings>(
node, message, messages_strings);
} else if (message == "WStrings") {
subscriber = subscribe_wstrings(node, message, messages_wstrings, received_messages);
publish<test_msgs::msg::typesupport_protobuf_cpp::WStringsTypeAdapter>(
publish<test_msgs::msg::pb::WStrings>(
node, message, messages_wstrings);
} else {
fprintf(stderr, "Unknown message argument '%s'\n", message.c_str());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,6 @@ TEMPLATE(
)
}@



@[for message in content.get_elements_of_type(Message)]@

@{
Expand All @@ -63,49 +61,32 @@ ros_type = ros_type(package_name, interface_path, message)
proto_type = protobuf_type(package_name, interface_path, message)
}@

namespace rclcpp
template<>
struct rclcpp::TypeAdapter<@(proto_type), @(ros_type)>
{

template<>
struct TypeAdapter<@(proto_type), @(ros_type)>
using is_specialized = std::true_type;
using custom_type = @(proto_type);
using ros_message_type = @(ros_type);

static
void
convert_to_ros_message(
const custom_type & source,
ros_message_type & destination)
{
using is_specialized = std::true_type;
using custom_type = @(proto_type);
using ros_message_type = @(ros_type);

static
void
convert_to_ros_message(
const custom_type & source,
ros_message_type & destination)
{
@("::".join(message.structure.namespaced_type.namespaces))::typesupport_protobuf_cpp::convert_to_ros(source, destination);
}

static
void
convert_to_custom(
const ros_message_type & source,
custom_type & destination)
{
@("::".join(message.structure.namespaced_type.namespaces))::typesupport_protobuf_cpp::convert_to_proto(source, destination);
}
};

}

@[for ns in message.structure.namespaced_type.namespaces]@
namespace @(ns)
{
@[end for]@
namespace typesupport_protobuf_cpp
{

using @(message.structure.namespaced_type.name)TypeAdapter = rclcpp::TypeAdapter<@(proto_type), @(ros_type)>;
@("::".join(message.structure.namespaced_type.namespaces))::typesupport_protobuf_cpp::convert_to_ros(source, destination);
}

static
void
convert_to_custom(
const ros_message_type & source,
custom_type & destination)
{
@("::".join(message.structure.namespaced_type.namespaces))::typesupport_protobuf_cpp::convert_to_proto(source, destination);
}
};

} // namespace typesupport_protobuf_cpp
@[ for ns in reversed(message.structure.namespaced_type.namespaces)]@
} // namespace @(ns)
@[ end for]@
RCLCPP_USING_CUSTOM_TYPE_AS_ROS_MESSAGE_TYPE(@(proto_type), @(ros_type));

@[end for]@