Skip to content

Commit

Permalink
Allow latching for ROS1 pub, and custom qos for ROS2 components (ros2…
Browse files Browse the repository at this point in the history
…#162)

Signed-off-by: Dhananjay Sathe <[email protected]>
  • Loading branch information
paulbovbel authored and dhananjaysathe committed Aug 22, 2019
1 parent 5620435 commit dd7662b
Show file tree
Hide file tree
Showing 2 changed files with 43 additions and 5 deletions.
27 changes: 24 additions & 3 deletions include/ros1_bridge/factory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,9 +47,10 @@ class Factory : public FactoryInterface
create_ros1_publisher(
ros::NodeHandle node,
const std::string & topic_name,
size_t queue_size)
size_t queue_size,
bool latch = false)
{
return node.advertise<ROS1_T>(topic_name, queue_size);
return node.advertise<ROS1_T>(topic_name, queue_size, latch);
}

rclcpp::PublisherBase::SharedPtr
Expand All @@ -63,6 +64,15 @@ class Factory : public FactoryInterface
return node->create_publisher<ROS2_T>(topic_name, custom_qos_profile);
}

rclcpp::PublisherBase::SharedPtr
create_ros2_publisher(
rclcpp::Node::SharedPtr node,
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile)
{
return node->create_publisher<ROS2_T>(topic_name, qos_profile);
}

ros::Subscriber
create_ros1_subscriber(
ros::NodeHandle node,
Expand Down Expand Up @@ -94,6 +104,17 @@ class Factory : public FactoryInterface
{
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_sensor_data;
custom_qos_profile.depth = queue_size;
return create_ros2_subscriber(node, topic_name, custom_qos_profile, ros1_pub, ros2_pub);
}

rclcpp::SubscriptionBase::SharedPtr
create_ros2_subscriber(
rclcpp::Node::SharedPtr node,
const std::string & topic_name,
const rmw_qos_profile_t & qos,
ros::Publisher ros1_pub,
rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr)
{
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.
Expand All @@ -104,7 +125,7 @@ class Factory : public FactoryInterface
msg, msg_info, ros1_pub, ros1_type_name, ros2_type_name, ros2_pub);
};
return node->create_subscription<ROS2_T>(
topic_name, callback, custom_qos_profile, nullptr, true);
topic_name, callback, qos, nullptr, true);
}

void convert_1_to_2(const void * ros1_msg, void * ros2_msg) override
Expand Down
21 changes: 19 additions & 2 deletions include/ros1_bridge/factory_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,8 @@ class FactoryInterface
create_ros1_publisher(
ros::NodeHandle node,
const std::string & topic_name,
size_t queue_size) = 0;
size_t queue_size,
bool latch = false) = 0;

virtual
rclcpp::PublisherBase::SharedPtr
Expand All @@ -59,6 +60,13 @@ class FactoryInterface
const std::string & topic_name,
size_t queue_size) = 0;

virtual
rclcpp::PublisherBase::SharedPtr
create_ros2_publisher(
rclcpp::Node::SharedPtr node,
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile) = 0;

virtual
ros::Subscriber
create_ros1_subscriber(
Expand All @@ -74,7 +82,16 @@ class FactoryInterface
const std::string & topic_name,
size_t queue_size,
ros::Publisher ros1_pub,
rclcpp::PublisherBase::SharedPtr ros2_pub) = 0;
rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr) = 0;

virtual
rclcpp::SubscriptionBase::SharedPtr
create_ros2_subscriber(
rclcpp::Node::SharedPtr node,
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile,
ros::Publisher ros1_pub,
rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr) = 0;

virtual
void
Expand Down

0 comments on commit dd7662b

Please sign in to comment.