22 # pragma clang diagnostic push
23 # pragma clang diagnostic ignored "-Wunused-parameter"
28 # pragma clang diagnostic pop
32 #include <ignition/transport/Node.hh>
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 "
62 <<
"A bidirectional bridge example:\n"
63 <<
" parameter_bridge /chatter@std_msgs/String@ignition.msgs"
65 <<
"A bridge from Ignition to ROS example:\n"
66 <<
" parameter_bridge /chatter@std_msgs/String[ignition.msgs"
68 <<
"A bridge from ROS to Ignition example:\n"
69 <<
" parameter_bridge /chatter@std_msgs/String]ignition.msgs"
70 <<
".StringMsg" << std::endl);
74 int main(
int argc,
char * argv[])
87 auto ign_node = std::make_shared<ignition::transport::Node>();
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;
94 const std::string delim =
"@";
95 const size_t queue_size = 10;
96 for (
auto i = 1; i < argc; ++i)
98 std::string arg = std::string(argv[i]);
99 auto delimPos = arg.find(delim);
100 if (delimPos == std::string::npos || delimPos == 0)
105 std::string topic_name = arg.substr(0, delimPos);
106 arg.erase(0, delimPos + delim.size());
112 delimPos = arg.find(
"@");
114 if (delimPos == std::string::npos || delimPos == 0)
116 delimPos = arg.find(
"[");
117 if (delimPos == std::string::npos || delimPos == 0)
119 delimPos = arg.find(
"]");
120 if (delimPos == std::string::npos || delimPos == 0)
135 std::string ros_type_name = arg.substr(0, delimPos);
136 arg.erase(0, delimPos + delim.size());
138 delimPos = arg.find(delim);
139 if (delimPos != std::string::npos || arg.empty())
144 std::string ign_type_name = arg;
152 bidirectional_handles.push_back(
155 ros_type_name, ign_type_name,
156 topic_name, queue_size));
159 ign_to_ros_handles.push_back(
162 ign_type_name, topic_name, queue_size,
163 ros_type_name, topic_name, queue_size));
166 ros_to_ign_handles.push_back(
169 ros_type_name, topic_name, queue_size,
170 ign_type_name, topic_name, queue_size));
174 catch (std::runtime_error &_e)
177 << topic_name <<
"] "
178 <<
"with ROS type [" << ros_type_name <<
"] and "
179 <<
"Ignition Transport type [" << ign_type_name <<
"]"
186 async_spinner.
start();
189 ignition::transport::waitForShutdown();