Skip to content

Commit

Permalink
print bridged type names
Browse files Browse the repository at this point in the history
  • Loading branch information
dirk-thomas committed Oct 6, 2017
1 parent 71d8aee commit a439f50
Show file tree
Hide file tree
Showing 2 changed files with 30 additions and 14 deletions.
42 changes: 29 additions & 13 deletions include/ros1_bridge/factory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,15 +26,19 @@

#include "ros1_bridge/factory_interface.hpp"

#define _ros1_bridge_type_to_name(x) #x

namespace ros1_bridge
{

template<typename ROS1_T, typename ROS2_T>
class Factory : public FactoryInterface
{
public:
Factory(
const std::string & ros1_type_name, const std::string & ros2_type_name)
: ros1_type_name_(ros1_type_name),
ros2_type_name_(ros2_type_name)
{}

ros::Publisher
create_ros1_publisher(
ros::NodeHandle node,
Expand Down Expand Up @@ -70,7 +74,9 @@ class Factory : public FactoryInterface
ops.datatype = ros::message_traits::datatype<ROS1_T>();
ops.helper = ros::SubscriptionCallbackHelperPtr(
new ros::SubscriptionCallbackHelperT<const ros::MessageEvent<ROS1_T const> &>(
boost::bind(&Factory<ROS1_T, ROS2_T>::ros1_callback, _1, ros2_pub)));
boost::bind(
&Factory<ROS1_T, ROS2_T>::ros1_callback,
_1, ros2_pub, ros1_type_name_, ros2_type_name_)));
return node.subscribe(ops);
}

Expand All @@ -83,10 +89,13 @@ class Factory : public FactoryInterface
{
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_sensor_data;
custom_qos_profile.depth = queue_size;
const std::string & ros1_type_name = ros1_type_name_;
const std::string & ros2_type_name = ros2_type_name_;
// TODO(wjwwood): use a lambda until create_subscription supports std/boost::bind.
auto callback =
[this, ros1_pub](const typename ROS2_T::SharedPtr msg) {
return this->ros2_callback(msg, ros1_pub);
[this, ros1_pub, ros1_type_name, ros2_type_name](const typename ROS2_T::SharedPtr msg) {
return this->ros2_callback(
msg, ros1_pub, ros1_type_name, ros2_type_name);
};
return node->create_subscription<ROS2_T>(
topic_name, callback, custom_qos_profile, nullptr, true);
Expand All @@ -96,7 +105,9 @@ class Factory : public FactoryInterface
static
void ros1_callback(
const ros::MessageEvent<ROS1_T const> & ros1_msg_event,
rclcpp::publisher::PublisherBase::SharedPtr ros2_pub)
rclcpp::publisher::PublisherBase::SharedPtr ros2_pub,
const std::string & ros1_type_name,
const std::string & ros2_type_name)
{
typename rclcpp::publisher::Publisher<ROS2_T>::SharedPtr typed_ros2_pub;
typed_ros2_pub =
Expand Down Expand Up @@ -125,23 +136,25 @@ class Factory : public FactoryInterface
auto ros2_msg = std::make_shared<ROS2_T>();
convert_1_to_2(*ros1_msg, *ros2_msg);
RCUTILS_LOG_INFO_ONCE_NAMED(
"ros1_bridge", "Passing message from ROS 1 "
_ros1_bridge_type_to_name(ROS1_T) " to ROS 2 "
_ros1_bridge_type_to_name(ROS2_T) " (showing msg only once per type)");
"ros1_bridge",
"Passing message from ROS 1 %s to ROS 2 %s (showing msg only once per type)",
ros1_type_name.c_str(), ros2_type_name.c_str());
typed_ros2_pub->publish(ros2_msg);
}

static
void ros2_callback(
typename ROS2_T::SharedPtr ros2_msg,
ros::Publisher ros1_pub)
ros::Publisher ros1_pub,
const std::string & ros1_type_name,
const std::string & ros2_type_name)
{
ROS1_T ros1_msg;
convert_2_to_1(*ros2_msg, ros1_msg);
RCUTILS_LOG_INFO_ONCE_NAMED(
"ros1_bridge", "Passing message from ROS 2 "
_ros1_bridge_type_to_name(ROS2_T) " to ROS 1 "
_ros1_bridge_type_to_name(ROS1_T) " (showing msg only once per type)");
"ros1_bridge",
"Passing message from ROS 2 %s to ROS 1 %s (showing msg only once per type)",
ros1_type_name.c_str(), ros2_type_name.c_str());
ros1_pub.publish(ros1_msg);
}

Expand All @@ -158,6 +171,9 @@ class Factory : public FactoryInterface
convert_2_to_1(
const ROS2_T & ros2_msg,
ROS1_T & ros1_msg);

std::string ros1_type_name_;
std::string ros2_type_name_;
};

template<class ROS1_T, class ROS2_T>
Expand Down
2 changes: 1 addition & 1 deletion resource/pkg_factories.cpp.em
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ get_factory_@(ros2_package_name)(const std::string & ros1_type_name, const std::
@(m.ros1_msg.package_name)::@(m.ros1_msg.message_name),
@(m.ros2_msg.package_name)::msg::@(m.ros2_msg.message_name)
>
>();
>("@(m.ros1_msg.package_name)/@(m.ros1_msg.message_name)", ros2_type_name);
}
@[end for]@
return std::shared_ptr<FactoryInterface>();
Expand Down

0 comments on commit a439f50

Please sign in to comment.