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 avoid deprecated API's #189

Merged
merged 1 commit into from
May 8, 2019
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
12 changes: 7 additions & 5 deletions include/ros1_bridge/factory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,9 +58,7 @@ class Factory : public FactoryInterface
const std::string & topic_name,
size_t queue_size)
{
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
custom_qos_profile.depth = queue_size;
return node->create_publisher<ROS2_T>(topic_name, custom_qos_profile);
return node->create_publisher<ROS2_T>(topic_name, rclcpp::QoS(rclcpp::KeepLast(queue_size)));
}

rclcpp::PublisherBase::SharedPtr
Expand All @@ -69,7 +67,9 @@ class Factory : public FactoryInterface
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile)
{
return node->create_publisher<ROS2_T>(topic_name, qos_profile);
auto qos = rclcpp::QoS(rclcpp::KeepAll());
qos.get_rmw_qos_profile() = qos_profile;
wjwwood marked this conversation as resolved.
Show resolved Hide resolved
return node->create_publisher<ROS2_T>(topic_name, qos);
}

ros::Subscriber
Expand Down Expand Up @@ -120,8 +120,10 @@ class Factory : public FactoryInterface
callback = std::bind(
&Factory<ROS1_T, ROS2_T>::ros2_callback, std::placeholders::_1, std::placeholders::_2,
ros1_pub, ros1_type_name_, ros2_type_name_, node->get_logger(), ros2_pub);
auto rclcpp_qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos));
wjwwood marked this conversation as resolved.
Show resolved Hide resolved
rclcpp_qos.get_rmw_qos_profile() = qos;
return node->create_subscription<ROS2_T>(
topic_name, callback, qos, nullptr, true);
topic_name, rclcpp_qos, callback, nullptr, true);
}

void convert_1_to_2(const void * ros1_msg, void * ros2_msg) override
Expand Down
4 changes: 2 additions & 2 deletions src/simple_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,15 +82,15 @@ int main(int argc, char * argv[])
rclcpp::init(argc, argv);
auto ros2_node = rclcpp::Node::make_shared("ros_bridge");
ros2_pub = ros2_node->create_publisher<std_msgs::msg::String>(
"chatter", rmw_qos_profile_sensor_data);
"chatter", rclcpp::SensorDataQoS());

// ROS 1 subscriber
ros::Subscriber ros1_sub = ros1_node.subscribe(
"chatter", 10, ros1ChatterCallback);

// ROS 2 subscriber
auto ros2_sub = ros2_node->create_subscription<std_msgs::msg::String>(
"chatter", ros2ChatterCallback, rmw_qos_profile_sensor_data, nullptr, true);
"chatter", rclcpp::SensorDataQoS(), ros2ChatterCallback, nullptr, true);

// ROS 1 asynchronous spinner
ros::AsyncSpinner async_spinner(1);
Expand Down
2 changes: 1 addition & 1 deletion src/simple_bridge_1_to_2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ int main(int argc, char * argv[])
// ROS 2 node and publisher
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("talker");
pub = node->create_publisher<std_msgs::msg::String>("chatter");
pub = node->create_publisher<std_msgs::msg::String>("chatter", 10);

// ROS 1 node and subscriber
ros::init(argc, argv, "listener");
Expand Down
2 changes: 1 addition & 1 deletion src/simple_bridge_2_to_1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ int main(int argc, char * argv[])
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("listener");
auto sub = node->create_subscription<std_msgs::msg::String>(
"chatter", chatterCallback, rmw_qos_profile_sensor_data);
"chatter", rclcpp::SensorDataQoS(), chatterCallback);

rclcpp::spin(node);

Expand Down