Skip to content

Commit

Permalink
Include visibility control header
Browse files Browse the repository at this point in the history
Signed-off-by: Gonzalo de Pedro <[email protected]>
  • Loading branch information
gdiaz-guevara authored and tfoote committed Jan 3, 2024
1 parent a9f58fa commit 8711162
Show file tree
Hide file tree
Showing 3 changed files with 25 additions and 20 deletions.
20 changes: 3 additions & 17 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,33 +6,19 @@ This project provides the ability to publish and subscribe with Protobuf Datatyp

#### Dependencies

* The type adapter that allows the user to publish from native ROS message or Protobuf data type
* Include the type adapter for the Protobuf data type message.
```cpp
#include "rclcpp/type_adapter.hpp"
```

* Next include the message to publish-subscribe, for example, a `string` message from `std_msgs`.
```cpp
#include "std_msgs/msg/string.hpp"
#include "std_msgs/msg/String.pb.h"
```

* Finally, include the type adapter for the Protobuf data type message.
```cpp
#include "std_msgs/rosidl_adapter_proto__visibility_control.h"
#include "std_msgs/msg/string__typeadapter_protobuf_cpp.hpp"
```
#### Publisher Example
```cpp
using MyAdaptedType = rclcpp::TypeAdapter<std_msgs::msg::pb::String, std_msgs::msg::String>;
publisher_ = this->create_publisher<MyAdaptedType>("topic", 10);
publisher_ = this->create_publisher<std_msgs::msg::typesupport_protobuf_cpp::StringTypeAdapter>("topic", 10);
```
To publish a message, it is only required to specify the adapter type to send the topic.

#### Subscriber Example
```cpp
using MyAdaptedType = rclcpp::TypeAdapter<std_msgs::msg::pb::String, std_msgs::msg::String>;
subscription2_ = this->create_subscription<MyAdaptedType>(
subscription2_ = this->create_subscription<std_msgs::msg::typesupport_protobuf_cpp::StringTypeAdapter>(
"topic", 10, std::bind(&MinimalSubscriber::topic_callback2, this, _1));
void topic_callback2(const std_msgs::msg::pb::String & msg) const
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,10 @@ def visibility_control_header(package_name):
return f'{package_name}/{_TYPE_SUPPORT_NAME}__visibility_control.h'


def adapter_visibility_control_header(package_name):
return f'{package_name}/rosidl_adapter_proto__visibility_control.h'


def ros_type_namespace(package_name, interface_path):
return _NAMESPACE_DELIMETER.join([package_name] + list(interface_path.parents[0].parts))

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ system_header_files = [
header_files = [
"rclcpp/type_adapter.hpp",
ros_message_header(package_name, interface_path),
adapter_visibility_control_header(package_name),
typesupport_message_header(package_name, interface_path),
visibility_control_header(package_name),
'rosidl_typesupport_protobuf/rosidl_generator_c_pkg_adapter.hpp',
Expand All @@ -51,8 +52,6 @@ TEMPLATE(
)
}@

namespace rclcpp
{


@[for message in content.get_elements_of_type(Message)]@
Expand All @@ -64,6 +63,9 @@ ros_type = ros_type(package_name, interface_path, message)
proto_type = protobuf_type(package_name, interface_path, message)
}@

namespace rclcpp
{

template<>
struct TypeAdapter<@(proto_type), @(ros_type)>
{
Expand All @@ -90,7 +92,20 @@ proto_type = protobuf_type(package_name, interface_path, message)
}
};

}

@[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)>;

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

@[end for]@

0 comments on commit 8711162

Please sign in to comment.