2828#include < fcntl.h>
2929#endif
3030
31+ #include < iterator>
3132#include < iostream>
3233#include < string>
3334#include < limits>
@@ -37,10 +38,15 @@ void showHelp()
3738{
3839 std::cout << " Usage: program <command>" << std::endl;
3940 std::cout << " List of commands:" << std::endl;
41+ #ifdef _WIN32
42+ std::cout << " udp <local_port>" << std::endl;
43+ std::cout << " tcp <local_port>" << std::endl;
44+ #else
4045 std::cout << " serial <device_name>" << std::endl;
4146 std::cout << " pseudo-serial" << std::endl;
4247 std::cout << " udp <local_port> [<discovery_port>]" << std::endl;
4348 std::cout << " tcp <local_port> [<discovery_port>]" << std::endl;
49+ #endif
4450}
4551
4652void initializationError ()
@@ -50,7 +56,7 @@ void initializationError()
5056 std::exit (EXIT_FAILURE);
5157}
5258
53- uint16_t parsePort (const char * str_port)
59+ uint16_t parsePort (const std::string& str_port)
5460{
5561 uint16_t valid_port = 0 ;
5662 try
@@ -70,73 +76,66 @@ uint16_t parsePort(const char* str_port)
7076 return valid_port;
7177}
7278
73-
74- class uros_agent : public rclcpp ::Node
75- {
76- public:
77- uros_agent () : Node(" uROS_Agent" )
78- {
79- }
80-
81- ~uros_agent ()
82- {
83- }
84-
85- private:
86-
87- };
88-
89-
9079int main (int argc, char ** argv)
9180{
92-
93- #ifdef __unix__
94- char exe_path[200 ];
95- ssize_t count = readlink (" /proc/self/exe" , exe_path, sizeof (exe_path));
96- if (count != -1 ) {
97- chdir (dirname (exe_path));
98- }
99- #endif
100-
101- bool initialized = false ;
81+ eprosima::uxr::Server* server = nullptr ;
82+ std::vector<std::string> cl (0 );
10283
103- #ifdef __unix__
104- if (argc == 2 && (strcmp (argv[1 ], " -h" ) == 0 || strcmp (argv[1 ], " --help" ) == 0 ))
84+ if (1 == argc)
10585 {
10686 showHelp ();
87+ std::cout << std::endl;
88+ std::cout << " Enter command: " ;
89+
90+ std::string raw_cl;
91+ std::getline (std::cin, raw_cl);
92+ std::istringstream iss (raw_cl);
93+ cl.insert (cl.begin (), std::istream_iterator<std::string>(iss), std::istream_iterator<std::string>());
94+ std::cout << raw_cl << std::endl;
10795 }
108- else if (argc >= 3 && strcmp (argv[ 1 ], " udp " ) == 0 )
96+ else
10997 {
110- std::cout << " UDP agent initialization... " ;
111- uint16_t port = parsePort (argv[2 ]);
112- eprosima::uxr::UDPServer* udp_server = (argc == 4 ) // discovery port
113- ? new eprosima::uxr::UDPServer (port, parsePort (argv[3 ]))
114- : new eprosima::uxr::UDPServer (port);
115- if (udp_server->run ())
98+ for (int i = 1 ; i < argc; ++i)
11699 {
117- initialized = true ;
100+ cl. push_back (argv[i]) ;
118101 }
119- std::cout << ((!initialized) ? " ERROR" : " OK" ) << std::endl;
120102 }
121- else if (argc >= 3 && strcmp (argv[1 ], " tcp" ) == 0 )
103+
104+ if ((1 == cl.size ()) && ((" -h" == cl[0 ]) || (" --help" == cl[0 ])))
105+ {
106+ showHelp ();
107+ }
108+ else if ((2 <= cl.size ()) && (" udp" == cl[0 ]))
109+ {
110+ std::cout << " UDP agent initialization... " ;
111+ uint16_t port = parsePort (cl[1 ]);
112+ #ifdef _WIN32
113+ server = new eprosima::uxr::UDPServer (port);
114+ #else
115+ server = (3 == cl.size ()) // discovery port
116+ ? new eprosima::uxr::UDPServer (port, parsePort (cl[2 ]))
117+ : new eprosima::uxr::UDPServer (port);
118+ #endif
119+ }
120+ else if ((2 <= cl.size ()) && (" tcp" == cl[0 ]))
122121 {
123122 std::cout << " TCP agent initialization... " ;
124- uint16_t port = parsePort (argv[2 ]);
125- eprosima::uxr::TCPServer* tcp_server = (argc == 4 ) // discovery port
126- ? new eprosima::uxr::TCPServer (port, parsePort (argv[3 ]))
127- : new eprosima::uxr::TCPServer (port);
128- if (tcp_server->run ())
129- {
130- initialized = true ;
131- }
132- std::cout << ((!initialized) ? " ERROR" : " OK" ) << std::endl;
123+ uint16_t port = parsePort (cl[1 ]);
124+ #ifdef _WIN32
125+ server = new eprosima::uxr::TCPServer (port);
126+ #else
127+ server = (3 == cl.size ()) // discovery port
128+ ? new eprosima::uxr::TCPServer (port, parsePort (cl[2 ]))
129+ : new eprosima::uxr::TCPServer (port);
130+ #endif
133131 }
134- else if (argc == 3 && strcmp (argv[1 ], " serial" ) == 0 )
132+ #ifndef _WIN32
133+ else if ((2 == cl.size ()) && (" serial" == cl[0 ]))
135134 {
136135 std::cout << " Serial agent initialization... " ;
137136
138137 /* Open serial device. */
139- int fd = open (argv[ 2 ] , O_RDWR | O_NOCTTY);
138+ int fd = open (cl[ 1 ]. c_str () , O_RDWR | O_NOCTTY);
140139 if (0 < fd)
141140 {
142141 struct termios tty_config;
@@ -181,18 +180,12 @@ int main(int argc, char** argv)
181180
182181 if (0 == tcsetattr (fd, TCSANOW, &tty_config))
183182 {
184- eprosima::uxr::SerialServer* serial_server = new eprosima::uxr::SerialServer (fd, 0 );
185- if (serial_server->run ())
186- {
187- initialized = true ;
188- }
183+ server = new eprosima::uxr::SerialServer (fd, 0 );
189184 }
190185 }
191186 }
192-
193- std::cout << ((!initialized) ? " ERROR" : " OK" ) << std::endl;
194187 }
195- else if (argc == 2 && strcmp (argv[ 1 ], " pseudo-serial" ) == 0 )
188+ else if (( 1 == cl. size ()) && ( " pseudo-serial" == cl[ 0 ]) )
196189 {
197190 std::cout << " Pseudo-Serial initialization... " ;
198191
@@ -208,78 +201,36 @@ int main(int argc, char** argv)
208201 cfmakeraw (&attr);
209202 tcflush (fd, TCIOFLUSH);
210203 tcsetattr (fd, TCSANOW, &attr);
204+ std::cout << " Device: " << dev << std::endl;
211205 }
212206 }
213-
214- /* Launch server. */
215- eprosima::uxr::SerialServer* serial_server = new eprosima::uxr::SerialServer (fd, 0x00 );
216- if (serial_server->run ())
217- {
218- initialized = true ;
219- }
220-
221- if (initialized)
222- {
223- std::cout << " OK" << std::endl;
224- std::cout << " Device: " << dev << std::endl;
225- }
226- else
227- {
228- std::cout << " ERROR" << std::endl;
229- }
207+ server = new eprosima::uxr::SerialServer (fd, 0x00 );
230208 }
209+ #endif
231210 else
232211 {
233212 initializationError ();
234213 }
235- #elif _WIN32
236- (void ) argc;
237- (void ) argv;
238-
239- std::string server_type = " " ;
240- std::cout << " Select server type [udp|tcp]: " ;
241- std::cin >> server_type;
242214
243- if (" udp " == server_type )
215+ if (nullptr != server )
244216 {
245- uint16_t port = 0 ;
246- std::cout << " Select port: " ;
247- std::cin >> port;
248-
249- std::cout << " UDP agent initialization.... " ;
250- eprosima::uxr::UDPServer* udp_server = new eprosima::uxr::UDPServer (port);
251- if (udp_server->run ())
217+ /* Launch server. */
218+ if (server->run ())
252219 {
253- initialized = true ;
220+ std::cout << " OK" << std::endl;
221+ std::cin.clear ();
222+ char exit_flag = 0 ;
223+ while (' q' != exit_flag)
224+ {
225+ std::cout << " Enter 'q' for exit" << std::endl;
226+ std::cin >> exit_flag;
227+ }
228+ server->stop ();
254229 }
255- std::cout << ((!initialized) ? " ERROR" : " OK" ) << std::endl;
256- }
257- else if (" tcp" == server_type)
258- {
259- uint16_t port = 0 ;
260- std::cout << " Select port: " ;
261- std::cin >> port;
262-
263- std::cout << " UDP agent initialization.... " ;
264- eprosima::uxr::TCPServer* tcp_server = new eprosima::uxr::TCPServer (port);
265- if (tcp_server->run ())
230+ else
266231 {
267- initialized = true ;
232+ std::cout << " ERROR " << std::endl ;
268233 }
269- std::cout << ((!initialized) ? " ERROR" : " OK" ) << std::endl;
270- }
271- else
272- {
273- std::cout << " Error server type" << std::endl;
274- }
275-
276- #endif
277-
278- if (initialized)
279- {
280- rclcpp::init (argc, argv);
281- rclcpp::spin (std::make_shared<uros_agent>());
282- rclcpp::shutdown ();
283234 }
284235
285236 return 0 ;
0 commit comments