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

Update for rclcpp namespace removals > > connects to ros2/rclcpp#416 #101

Merged
merged 6 commits into from
Dec 5, 2017
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
10 changes: 5 additions & 5 deletions include/ros1_bridge/bridge.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,12 @@ namespace ros1_bridge
struct Bridge1to2Handles
{
ros::Subscriber ros1_subscriber;
rclcpp::publisher::PublisherBase::SharedPtr ros2_publisher;
rclcpp::PublisherBase::SharedPtr ros2_publisher;
};

struct Bridge2to1Handles
{
rclcpp::subscription::SubscriptionBase::SharedPtr ros2_subscriber;
rclcpp::SubscriptionBase::SharedPtr ros2_subscriber;
ros::Publisher ros1_publisher;
};

Expand Down Expand Up @@ -69,7 +69,7 @@ get_factory(
Bridge1to2Handles
create_bridge_from_1_to_2(
ros::NodeHandle ros1_node,
rclcpp::node::Node::SharedPtr ros2_node,
rclcpp::Node::SharedPtr ros2_node,
const std::string & ros1_type_name,
const std::string & ros1_topic_name,
size_t subscriber_queue_size,
Expand All @@ -92,7 +92,7 @@ create_bridge_from_1_to_2(

Bridge2to1Handles
create_bridge_from_2_to_1(
rclcpp::node::Node::SharedPtr ros2_node,
rclcpp::Node::SharedPtr ros2_node,
ros::NodeHandle ros1_node,
const std::string & ros2_type_name,
const std::string & ros2_topic_name,
Expand All @@ -117,7 +117,7 @@ create_bridge_from_2_to_1(
BridgeHandles
create_bidirectional_bridge(
ros::NodeHandle ros1_node,
rclcpp::node::Node::SharedPtr ros2_node,
rclcpp::Node::SharedPtr ros2_node,
const std::string & ros1_type_name,
const std::string & ros2_type_name,
const std::string & topic_name,
Expand Down
26 changes: 13 additions & 13 deletions include/ros1_bridge/factory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,9 @@ class Factory : public FactoryInterface
return node.advertise<ROS1_T>(topic_name, queue_size);
}

rclcpp::publisher::PublisherBase::SharedPtr
rclcpp::PublisherBase::SharedPtr
create_ros2_publisher(
rclcpp::node::Node::SharedPtr node,
rclcpp::Node::SharedPtr node,
const std::string & topic_name,
size_t queue_size)
{
Expand All @@ -64,7 +64,7 @@ class Factory : public FactoryInterface
ros::NodeHandle node,
const std::string & topic_name,
size_t queue_size,
rclcpp::publisher::PublisherBase::SharedPtr ros2_pub)
rclcpp::PublisherBase::SharedPtr ros2_pub)
{
// workaround for https://github.com/ros/roscpp_core/issues/22 to get the connection header
ros::SubscribeOptions ops;
Expand All @@ -80,9 +80,9 @@ class Factory : public FactoryInterface
return node.subscribe(ops);
}

rclcpp::subscription::SubscriptionBase::SharedPtr
rclcpp::SubscriptionBase::SharedPtr
create_ros2_subscriber(
rclcpp::node::Node::SharedPtr node,
rclcpp::Node::SharedPtr node,
const std::string & topic_name,
size_t queue_size,
ros::Publisher ros1_pub)
Expand All @@ -105,13 +105,13 @@ class Factory : public FactoryInterface
static
void ros1_callback(
const ros::MessageEvent<ROS1_T const> & ros1_msg_event,
rclcpp::publisher::PublisherBase::SharedPtr ros2_pub,
rclcpp::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;
typename rclcpp::Publisher<ROS2_T>::SharedPtr typed_ros2_pub;
typed_ros2_pub =
std::dynamic_pointer_cast<typename rclcpp::publisher::Publisher<ROS2_T>>(ros2_pub);
std::dynamic_pointer_cast<typename rclcpp::Publisher<ROS2_T>>(ros2_pub);

if (!typed_ros2_pub) {
throw std::runtime_error("Invalid type for publisher");
Expand Down Expand Up @@ -199,18 +199,18 @@ class ServiceFactory : public ServiceFactoryInterface
}

bool forward_1_to_2(
rclcpp::client::ClientBase::SharedPtr cli,
rclcpp::ClientBase::SharedPtr cli,
const ROS1Request & request1, ROS1Response & response1)
{
auto client = std::dynamic_pointer_cast<rclcpp::client::Client<ROS2_T>>(cli);
auto client = std::dynamic_pointer_cast<rclcpp::Client<ROS2_T>>(cli);
if (!client) {
fprintf(stderr, "Failed to get the client.\n");
return false;
}
auto request2 = std::make_shared<ROS2Request>();
translate_1_to_2(request1, *request2);
while (!client->wait_for_service(std::chrono::seconds(1))) {
if (!rclcpp::utilities::ok()) {
if (!rclcpp::ok()) {
fprintf(stderr, "Client was interrupted while waiting for the service. Exiting.\n");
return false;
}
Expand All @@ -229,7 +229,7 @@ class ServiceFactory : public ServiceFactoryInterface
}

ServiceBridge1to2 service_bridge_1_to_2(
ros::NodeHandle & ros1_node, rclcpp::node::Node::SharedPtr ros2_node, const std::string & name)
ros::NodeHandle & ros1_node, rclcpp::Node::SharedPtr ros2_node, const std::string & name)
{
ServiceBridge1to2 bridge;
bridge.client = ros2_node->create_client<ROS2_T>(name);
Expand All @@ -240,7 +240,7 @@ class ServiceFactory : public ServiceFactoryInterface
}

ServiceBridge2to1 service_bridge_2_to_1(
ros::NodeHandle & ros1_node, rclcpp::node::Node::SharedPtr ros2_node, const std::string & name)
ros::NodeHandle & ros1_node, rclcpp::Node::SharedPtr ros2_node, const std::string & name)
{
ServiceBridge2to1 bridge;
bridge.client = ros1_node.serviceClient<ROS1_T>(name);
Expand Down
18 changes: 9 additions & 9 deletions include/ros1_bridge/factory_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,12 @@ namespace ros1_bridge
struct ServiceBridge1to2
{
ros::ServiceServer server;
rclcpp::client::ClientBase::SharedPtr client;
rclcpp::ClientBase::SharedPtr client;
};

struct ServiceBridge2to1
{
rclcpp::service::ServiceBase::SharedPtr server;
rclcpp::ServiceBase::SharedPtr server;
ros::ServiceClient client;
};

Expand All @@ -53,9 +53,9 @@ class FactoryInterface
size_t queue_size) = 0;

virtual
rclcpp::publisher::PublisherBase::SharedPtr
rclcpp::PublisherBase::SharedPtr
create_ros2_publisher(
rclcpp::node::Node::SharedPtr node,
rclcpp::Node::SharedPtr node,
const std::string & topic_name,
size_t queue_size) = 0;

Expand All @@ -65,12 +65,12 @@ class FactoryInterface
ros::NodeHandle node,
const std::string & topic_name,
size_t queue_size,
rclcpp::publisher::PublisherBase::SharedPtr ros2_pub) = 0;
rclcpp::PublisherBase::SharedPtr ros2_pub) = 0;

virtual
rclcpp::subscription::SubscriptionBase::SharedPtr
rclcpp::SubscriptionBase::SharedPtr
create_ros2_subscriber(
rclcpp::node::Node::SharedPtr node,
rclcpp::Node::SharedPtr node,
const std::string & topic_name,
size_t queue_size,
ros::Publisher ros1_pub) = 0;
Expand All @@ -80,10 +80,10 @@ class ServiceFactoryInterface
{
public:
virtual ServiceBridge1to2 service_bridge_1_to_2(
ros::NodeHandle &, rclcpp::node::Node::SharedPtr, const std::string &) = 0;
ros::NodeHandle &, rclcpp::Node::SharedPtr, const std::string &) = 0;

virtual ServiceBridge2to1 service_bridge_2_to_1(
ros::NodeHandle &, rclcpp::node::Node::SharedPtr, const std::string &) = 0;
ros::NodeHandle &, rclcpp::Node::SharedPtr, const std::string &) = 0;
};

} // namespace ros1_bridge
Expand Down
6 changes: 3 additions & 3 deletions src/dynamic_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ bool parse_command_options(

void update_bridge(
ros::NodeHandle & ros1_node,
rclcpp::node::Node::SharedPtr ros2_node,
rclcpp::Node::SharedPtr ros2_node,
const std::map<std::string, std::string> & ros1_publishers,
const std::map<std::string, std::string> & ros1_subscribers,
const std::map<std::string, std::string> & ros2_publishers,
Expand Down Expand Up @@ -458,7 +458,7 @@ int main(int argc, char * argv[])

// ROS 2 node
rclcpp::init(argc, argv);
auto ros2_node = rclcpp::node::Node::make_shared("ros_bridge");
auto ros2_node = rclcpp::Node::make_shared("ros_bridge");

// mapping of available topic names to type names
std::map<std::string, std::string> ros1_publishers;
Expand Down Expand Up @@ -758,7 +758,7 @@ int main(int argc, char * argv[])

// ROS 2 spinning loop
rclcpp::executors::SingleThreadedExecutor executor;
while (ros1_node.ok() && rclcpp::utilities::ok()) {
while (ros1_node.ok() && rclcpp::ok()) {
executor.spin_node_once(ros2_node);
}

Expand Down
4 changes: 2 additions & 2 deletions src/parameter_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ int main(int argc, char * argv[])

// ROS 2 node
rclcpp::init(argc, argv);
auto ros2_node = rclcpp::node::Node::make_shared("ros_bridge");
auto ros2_node = rclcpp::Node::make_shared("ros_bridge");

std::list<ros1_bridge::BridgeHandles> all_handles;

Expand Down Expand Up @@ -94,7 +94,7 @@ int main(int argc, char * argv[])

// ROS 2 spinning loop
rclcpp::executors::SingleThreadedExecutor executor;
while (ros1_node.ok() && rclcpp::utilities::ok()) {
while (ros1_node.ok() && rclcpp::ok()) {
executor.spin_node_once(ros2_node, std::chrono::milliseconds(1000));
}

Expand Down
6 changes: 3 additions & 3 deletions src/simple_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ void ros2ChatterCallback(const std_msgs::msg::String::SharedPtr ros2_msg)
}


rclcpp::publisher::Publisher<std_msgs::msg::String>::SharedPtr ros2_pub;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr ros2_pub;

void ros1ChatterCallback(const ros::MessageEvent<std_msgs::String const> & ros1_msg_event)
{
Expand Down Expand Up @@ -80,7 +80,7 @@ int main(int argc, char * argv[])

// ROS 2 node and publisher
rclcpp::init(argc, argv);
auto ros2_node = rclcpp::node::Node::make_shared("ros_bridge");
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);

Expand All @@ -98,7 +98,7 @@ int main(int argc, char * argv[])

// ROS 2 spinning loop
rclcpp::executors::SingleThreadedExecutor executor;
while (ros1_node.ok() && rclcpp::utilities::ok()) {
while (ros1_node.ok() && rclcpp::ok()) {
executor.spin_node_once(ros2_node, std::chrono::milliseconds(1000));
}

Expand Down
4 changes: 2 additions & 2 deletions src/simple_bridge_1_to_2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
#include "std_msgs/msg/string.hpp"


rclcpp::publisher::Publisher<std_msgs::msg::String>::SharedPtr pub;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub;

void chatterCallback(const std_msgs::String::ConstPtr & ros1_msg)
{
Expand All @@ -47,7 +47,7 @@ int main(int argc, char * argv[])
{
// ROS 2 node and publisher
rclcpp::init(argc, argv);
auto node = rclcpp::node::Node::make_shared("talker");
auto node = rclcpp::Node::make_shared("talker");
pub = node->create_publisher<std_msgs::msg::String>("chatter");

// ROS 1 node and subscriber
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 @@ -51,7 +51,7 @@ int main(int argc, char * argv[])

// ROS 2 node and subscriber
rclcpp::init(argc, argv);
auto node = rclcpp::node::Node::make_shared("listener");
auto node = rclcpp::Node::make_shared("listener");
auto sub = node->create_subscription<std_msgs::msg::String>(
"chatter", chatterCallback, rmw_qos_profile_sensor_data);

Expand Down
4 changes: 2 additions & 2 deletions src/static_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ int main(int argc, char * argv[])

// ROS 2 node
rclcpp::init(argc, argv);
auto ros2_node = rclcpp::node::Node::make_shared("ros_bridge");
auto ros2_node = rclcpp::Node::make_shared("ros_bridge");

// bridge one example topic
std::string topic_name = "chatter";
Expand All @@ -55,7 +55,7 @@ int main(int argc, char * argv[])

// ROS 2 spinning loop
rclcpp::executors::SingleThreadedExecutor executor;
while (ros1_node.ok() && rclcpp::utilities::ok()) {
while (ros1_node.ok() && rclcpp::ok()) {
executor.spin_node_once(ros2_node, std::chrono::milliseconds(1000));
}

Expand Down