parameter_bridge.cpp
Go to the documentation of this file.
1 // Copyright 2018 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <iostream>
16 #include <list>
17 #include <memory>
18 #include <string>
19 
20 // include ROS
21 #ifdef __clang__
22 # pragma clang diagnostic push
23 # pragma clang diagnostic ignored "-Wunused-parameter"
24 #endif
25 #include <ros/ros.h>
26 #include <ros/console.h>
27 #ifdef __clang__
28 # pragma clang diagnostic pop
29 #endif
30 
31 // include Ignition Transport
32 #include <ignition/transport/Node.hh>
33 
34 #include "bridge.hpp"
35 
36 // Direction of bridge.
38 {
39  // Both directions.
41  // Only from IGN to ROS
43  // Only from ROS to IGN
45 };
46 
48 void usage()
49 {
51  "Bridge a collection of ROS and Ignition Transport topics.\n\n"
52  << " parameter_bridge <topic@ROS_type(@,[,])Ign_type> .. "
53  << " <topic@ROS_type(@,[,])Ign_type>\n\n"
54  << "The first @ symbol delimits the topic name from the message types.\n"
55  << "Following the first @ symbol is the ROS message type.\n"
56  << "The ROS message type is followed by an @, [, or ] symbol where\n"
57  << " @ == a bidirectional bridge, \n"
58  << " [ == a bridge from Ignition to ROS,\n"
59  << " ] == a bridge from ROS to Ignition.\n"
60  << "Following the direction symbol is the Ignition Transport message "
61  << "type.\n\n"
62  << "A bidirectional bridge example:\n"
63  << " parameter_bridge /chatter@std_msgs/String@ignition.msgs"
64  << ".StringMsg\n\n"
65  << "A bridge from Ignition to ROS example:\n"
66  << " parameter_bridge /chatter@std_msgs/String[ignition.msgs"
67  << ".StringMsg\n\n"
68  << "A bridge from ROS to Ignition example:\n"
69  << " parameter_bridge /chatter@std_msgs/String]ignition.msgs"
70  << ".StringMsg" << std::endl);
71 }
72 
74 int main(int argc, char * argv[])
75 {
76  if (argc < 2)
77  {
78  usage();
79  return -1;
80  }
81 
82  // ROS node
83  ros::init(argc, argv, "ros_ign_bridge");
84  ros::NodeHandle ros_node;
85 
86  // Ignition node
87  auto ign_node = std::make_shared<ignition::transport::Node>();
88 
89  std::list<ros_ign_bridge::BridgeHandles> bidirectional_handles;
90  std::list<ros_ign_bridge::BridgeIgnToRosHandles> ign_to_ros_handles;
91  std::list<ros_ign_bridge::BridgeRosToIgnHandles> ros_to_ign_handles;
92 
93  // Parse all arguments.
94  const std::string delim = "@";
95  const size_t queue_size = 10;
96  for (auto i = 1; i < argc; ++i)
97  {
98  std::string arg = std::string(argv[i]);
99  auto delimPos = arg.find(delim);
100  if (delimPos == std::string::npos || delimPos == 0)
101  {
102  usage();
103  return -1;
104  }
105  std::string topic_name = arg.substr(0, delimPos);
106  arg.erase(0, delimPos + delim.size());
107 
108  // Get the direction delimeter, which should be one of:
109  // @ == bidirectional, or
110  // [ == only from IGN to ROS, or
111  // ] == only from ROS to IGN.
112  delimPos = arg.find("@");
113  Direction direction = BIDIRECTIONAL;
114  if (delimPos == std::string::npos || delimPos == 0)
115  {
116  delimPos = arg.find("[");
117  if (delimPos == std::string::npos || delimPos == 0)
118  {
119  delimPos = arg.find("]");
120  if (delimPos == std::string::npos || delimPos == 0)
121  {
122  usage();
123  return -1;
124  }
125  else
126  {
127  direction = FROM_ROS_TO_IGN;
128  }
129  }
130  else
131  {
132  direction = FROM_IGN_TO_ROS;
133  }
134  }
135  std::string ros_type_name = arg.substr(0, delimPos);
136  arg.erase(0, delimPos + delim.size());
137 
138  delimPos = arg.find(delim);
139  if (delimPos != std::string::npos || arg.empty())
140  {
141  usage();
142  return -1;
143  }
144  std::string ign_type_name = arg;
145 
146  try
147  {
148  switch (direction)
149  {
150  default:
151  case BIDIRECTIONAL:
152  bidirectional_handles.push_back(
154  ros_node, ign_node,
155  ros_type_name, ign_type_name,
156  topic_name, queue_size));
157  break;
158  case FROM_IGN_TO_ROS:
159  ign_to_ros_handles.push_back(
161  ign_node, ros_node,
162  ign_type_name, topic_name, queue_size,
163  ros_type_name, topic_name, queue_size));
164  break;
165  case FROM_ROS_TO_IGN:
166  ros_to_ign_handles.push_back(
168  ros_node, ign_node,
169  ros_type_name, topic_name, queue_size,
170  ign_type_name, topic_name, queue_size));
171  break;
172  }
173  }
174  catch (std::runtime_error &_e)
175  {
176  ROS_ERROR_STREAM("Failed to create a bridge for topic ["
177  << topic_name << "] "
178  << "with ROS type [" << ros_type_name << "] and "
179  << "Ignition Transport type [" << ign_type_name << "]"
180  << std::endl);
181  }
182  }
183 
184  // ROS asynchronous spinner
185  ros::AsyncSpinner async_spinner(1);
186  async_spinner.start();
187 
188  // Zzzzzz.
189  ignition::transport::waitForShutdown();
190 
191  return 0;
192 }
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
FROM_ROS_TO_IGN
@ FROM_ROS_TO_IGN
Definition: parameter_bridge.cpp:44
usage
void usage()
Definition: parameter_bridge.cpp:48
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
main
int main(int argc, char *argv[])
Definition: parameter_bridge.cpp:74
ros::AsyncSpinner::start
void start()
ros.h
ros::AsyncSpinner
ros_ign_bridge::create_bridge_from_ros_to_ign
BridgeRosToIgnHandles create_bridge_from_ros_to_ign(ros::NodeHandle ros_node, std::shared_ptr< ignition::transport::Node > ign_node, const std::string &ros_type_name, const std::string &ros_topic_name, size_t subscriber_queue_size, const std::string &ign_type_name, const std::string &ign_topic_name, size_t publisher_queue_size)
Definition: bridge.hpp:52
ros_ign_bridge::create_bridge_from_ign_to_ros
BridgeIgnToRosHandles create_bridge_from_ign_to_ros(std::shared_ptr< ignition::transport::Node > ign_node, ros::NodeHandle ros_node, const std::string &ign_type_name, const std::string &ign_topic_name, size_t subscriber_queue_size, const std::string &ros_type_name, const std::string &ros_topic_name, size_t publisher_queue_size)
Definition: bridge.hpp:76
Direction
Direction
Definition: parameter_bridge.cpp:37
console.h
FROM_IGN_TO_ROS
@ FROM_IGN_TO_ROS
Definition: parameter_bridge.cpp:42
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
ros_ign_bridge::create_bidirectional_bridge
BridgeHandles create_bidirectional_bridge(ros::NodeHandle ros_node, std::shared_ptr< ignition::transport::Node > ign_node, const std::string &ros_type_name, const std::string &ign_type_name, const std::string &topic_name, size_t queue_size=10)
Definition: bridge.hpp:100
bridge.hpp
BIDIRECTIONAL
@ BIDIRECTIONAL
Definition: parameter_bridge.cpp:40
ros::NodeHandle


ros_ign_bridge
Author(s):
autogenerated on Sat Mar 11 2023 04:02:16