Skip to content
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
2 changes: 1 addition & 1 deletion micro_ros_agent/bin/Xml_interface_gen.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)),'..'))

from rosidl_cmake import read_generator_arguments
from rosidl_parser import UnknownMessageType
from rosidl_adapter.parser import UnknownMessageType
from micro_ros_agent import generate_XML


Expand Down
10 changes: 5 additions & 5 deletions micro_ros_agent/micro_ros_agent/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,12 @@

from rosidl_cmake import convert_camel_case_to_lower_case_underscore
from rosidl_cmake import expand_template
from rosidl_cmake import extract_message_types
from rosidl_cmake import get_newest_modification_time
from rosidl_parser import parse_message_file
from rosidl_parser import parse_service_file
from rosidl_parser import validate_field_types
from rosidl_adapter.parser import parse_message_file
from rosidl_adapter.parser import parse_service_file
from rosidl_adapter.parser import validate_field_types

from rosidl_cmake import generate_files

def GetPackage(Dir):

Expand Down Expand Up @@ -214,4 +214,4 @@ def generate_XML(args):
#f = open(os.path.join(args['output_dir'], 'demofile.txt'), 'w+')
#f.write("%s\n" % spec)
#f.close()
return 0
return 0
254 changes: 52 additions & 202 deletions micro_ros_agent/src/main.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@

// Copyright 2018 Proyectos y Sistemas de Mantenimiento SL (eProsima).
// Copyright 2017-present Proyectos y Sistemas de Mantenimiento SL (eProsima).
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -13,225 +12,76 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifdef _WIN32
#include <uxr/agent/transport/udp/UDPServerWindows.hpp>
#include <uxr/agent/transport/tcp/TCPServerWindows.hpp>

#elif __unix__
#include <unistd.h>
#include <libgen.h>

#include <uxr/agent/transport/serial/SerialServerLinux.hpp>
#include <uxr/agent/transport/udp/UDPServerLinux.hpp>
#include <uxr/agent/transport/tcp/TCPServerLinux.hpp>
#include <termios.h>
#include <fcntl.h>
#endif

#include <iterator>
#include <iostream>
#include <string>
#include <limits>
#include "rclcpp/rclcpp.hpp"

void showHelp()
{
std::cout << "Usage: program <command>" << std::endl;
std::cout << "List of commands:" << std::endl;
#ifdef _WIN32
std::cout << " udp <local_port>" << std::endl;
std::cout << " tcp <local_port>" << std::endl;
#else
std::cout << " serial <device_name>" << std::endl;
std::cout << " pseudo-serial" << std::endl;
std::cout << " udp <local_port> [<discovery_port>]" << std::endl;
std::cout << " tcp <local_port> [<discovery_port>]" << std::endl;
#endif
}

void initializationError()
{
std::cout << "Error: Invalid arguments." << std::endl;
showHelp();
std::exit(EXIT_FAILURE);
}

uint16_t parsePort(const std::string& str_port)
{
uint16_t valid_port = 0;
try
{
int port = std::stoi(str_port);
if(port > (std::numeric_limits<uint16_t>::max)())
{
std::cout << "Error: port number '" << port << "out of range." << std::endl;
initializationError();
}
valid_port = uint16_t(port);
}
catch (const std::invalid_argument& )
{
initializationError();
}
return valid_port;
}
#include <uxr/agent/utils/CLI.hpp>
#include <csignal>

int main(int argc, char** argv)
{
eprosima::uxr::Server* server = nullptr;
std::vector<std::string> cl(0);

if (1 == argc)
{
showHelp();
std::cout << std::endl;
std::cout << "Enter command: ";

std::string raw_cl;
std::getline(std::cin, raw_cl);
std::istringstream iss(raw_cl);
cl.insert(cl.begin(), std::istream_iterator<std::string>(iss), std::istream_iterator<std::string>());
std::cout << raw_cl << std::endl;
}
else
{
for (int i = 1; i < argc; ++i)
{
cl.push_back(argv[i]);
}
}

if((1 == cl.size()) && (("-h" == cl[0]) || ("--help" == cl[0])))
{
showHelp();
}
else if((2 <= cl.size()) && ("udp" == cl[0]))
#ifndef _WIN32
sigset_t signals;
sigemptyset(&signals);
if(sigaddset(&signals, SIGINT) && sigaddset(&signals, SIGTERM))
{
std::cout << "UDP agent initialization... ";
uint16_t port = parsePort(cl[1]);
#ifdef _WIN32
server = new eprosima::uxr::UDPServer(port);
#else
server = (3 == cl.size()) //discovery port
? new eprosima::uxr::UDPServer(port, parsePort(cl[2]))
: new eprosima::uxr::UDPServer(port);
#endif
std::cerr << "Wrong signalset" << std::endl;
std::exit(EXIT_FAILURE);
}
else if((2 <= cl.size()) && ("tcp" == cl[0]))
{
std::cout << "TCP agent initialization... ";
uint16_t port = parsePort(cl[1]);
#ifdef _WIN32
server = new eprosima::uxr::TCPServer(port);
#else
server = (3 == cl.size()) //discovery port
? new eprosima::uxr::TCPServer(port, parsePort(cl[2]))
: new eprosima::uxr::TCPServer(port);
sigprocmask( SIG_BLOCK, &signals, nullptr );
#endif
}
#ifndef _WIN32
else if((2 == cl.size()) && ("serial" == cl[0]))
{
std::cout << "Serial agent initialization... ";

/* Open serial device. */
int fd = open(cl[1].c_str(), O_RDWR | O_NOCTTY);
if (0 < fd)
{
struct termios tty_config;
memset(&tty_config, 0, sizeof(tty_config));
if (0 == tcgetattr(fd, &tty_config))
{
/* Setting CONTROL OPTIONS. */
tty_config.c_cflag |= CREAD; // Enable read.
tty_config.c_cflag |= CLOCAL; // Set local mode.
tty_config.c_cflag &= ~PARENB; // Disable parity.
tty_config.c_cflag &= ~CSTOPB; // Set one stop bit.
tty_config.c_cflag &= ~CSIZE; // Mask the character size bits.
tty_config.c_cflag |= CS8; // Set 8 data bits.
tty_config.c_cflag &= ~CRTSCTS; // Disable hardware flow control.

/* Setting LOCAL OPTIONS. */
tty_config.c_lflag &= ~ICANON; // Set non-canonical input.
tty_config.c_lflag &= ~ECHO; // Disable echoing of input characters.
tty_config.c_lflag &= ~ECHOE; // Disable echoing the erase character.
tty_config.c_lflag &= ~ISIG; // Disable SIGINTR, SIGSUSP, SIGDSUSP and SIGQUIT signals.

/* Setting INPUT OPTIONS. */
tty_config.c_iflag &= ~IXON; // Disable output software flow control.
tty_config.c_iflag &= ~IXOFF; // Disable input software flow control.
tty_config.c_iflag &= ~INPCK; // Disable parity check.
tty_config.c_iflag &= ~ISTRIP; // Disable strip parity bits.
tty_config.c_iflag &= ~IGNBRK; // No ignore break condition.
tty_config.c_iflag &= ~IGNCR; // No ignore carrier return.
tty_config.c_iflag &= ~INLCR; // No map NL to CR.
tty_config.c_iflag &= ~ICRNL; // No map CR to NL.

/* Setting OUTPUT OPTIONS. */
tty_config.c_oflag &= ~OPOST; // Set raw output.

/* Setting OUTPUT CHARACTERS. */
tty_config.c_cc[VMIN] = 10;
tty_config.c_cc[VTIME] = 1;

/* Setting BAUD RATE. */
cfsetispeed(&tty_config, B115200);
cfsetospeed(&tty_config, B115200);
/* CLI application. */
CLI::App app("micro-ROS Agent");
app.require_subcommand(1, 1);
app.get_formatter()->column_width(42);

if (0 == tcsetattr(fd, TCSANOW, &tty_config))
{
server = new eprosima::uxr::SerialServer(fd, 0);
}
}
}
}
else if ((1 == cl.size()) && ("pseudo-serial" == cl[0]))
{
std::cout << "Pseudo-Serial initialization... ";

/* Open pseudo-terminal. */
char* dev = NULL;
int fd = posix_openpt(O_RDWR | O_NOCTTY);
if (-1 != fd)
{
if (grantpt(fd) == 0 && unlockpt(fd) == 0 && (dev = ptsname(fd)))
{
struct termios attr;
tcgetattr(fd, &attr);
cfmakeraw(&attr);
tcflush(fd, TCIOFLUSH);
tcsetattr(fd, TCSANOW, &attr);
std::cout << "Device: " << dev << std::endl;
}
}
server = new eprosima::uxr::SerialServer(fd, 0x00);
}
/* CLI subcommands. */
eprosima::uxr::cli::UDPv4Subcommand udpv4_subcommand(app);
eprosima::uxr::cli::UDPv6Subcommand udpv6_subcommand(app);
eprosima::uxr::cli::TCPv4Subcommand tcpv4_subcommand(app);
eprosima::uxr::cli::TCPv6Subcommand tcpv6_subcommand(app);
#ifndef _WIN32
eprosima::uxr::cli::SerialSubcommand serial_subcommand(app);
eprosima::uxr::cli::PseudoSerialSubcommand pseudo_serial_subcommand(app);
#endif
else
eprosima::uxr::cli::ExitSubcommand exit_subcommand(app);

/* CLI parse. */
std::string cli_input{};
for (int i = 1; i < argc; ++i)
{
initializationError();
cli_input.append(argv[i]);
cli_input.append(" ");
}

if (nullptr != server)
while (true)
{
/* Launch server. */
if (server->run())
try
{
std::cout << "OK" << std::endl;
std::cin.clear();
char exit_flag = 0;
while ('q' != exit_flag)
{
std::cout << "Enter 'q' for exit" << std::endl;
std::cin >> exit_flag;
}
server->stop();
app.parse(cli_input);
break;
}
else
catch (const CLI::ParseError& e)
{
std::cout << "ERROR" << std::endl;
app.exit(e);
std::cin.clear();
std::cout << std::endl;
std::cout << "Enter command: ";
std::getline(std::cin, cli_input);
}
}

#ifdef _WIN32
/* Waiting until exit. */
std::cin.clear();
char exit_flag = 0;
while ('q' != exit_flag)
{
std::cin >> exit_flag;
}
#else
/* Wait for SIGTERM/SIGINT instead, as reading from stdin may be redirected to /dev/null. */
int n_signal = 0;
sigwait(&signals, &n_signal);
#endif
return 0;
}