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 uROS_Agent/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ normalize_path(_DEFAULT_FASTRTPS_PROFILES_PATH "${_DEFAULT_FASTRTPS_PROFILES_PAT


# Get colcon call dir
get_filename_component(_COLCON_CALL_DIR "${CMAKE_INSTALL_PREFIX}" DIRECTORY)
get_filename_component(_COLCON_CALL_DIR "${PROJECT_BINARY_DIR}" DIRECTORY)
get_filename_component(_COLCON_CALL_DIR "${_COLCON_CALL_DIR}" DIRECTORY)


Expand Down
187 changes: 69 additions & 118 deletions uROS_Agent/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
#include <fcntl.h>
#endif

#include <iterator>
#include <iostream>
#include <string>
#include <limits>
Expand All @@ -37,10 +38,15 @@ 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()
Expand All @@ -50,7 +56,7 @@ void initializationError()
std::exit(EXIT_FAILURE);
}

uint16_t parsePort(const char* str_port)
uint16_t parsePort(const std::string& str_port)
{
uint16_t valid_port = 0;
try
Expand All @@ -70,73 +76,66 @@ uint16_t parsePort(const char* str_port)
return valid_port;
}


class uros_agent : public rclcpp::Node
{
public:
uros_agent() : Node("uROS_Agent")
{
}

~uros_agent()
{
}

private:

};


int main(int argc, char** argv)
{

#ifdef __unix__
char exe_path[200];
ssize_t count = readlink("/proc/self/exe", exe_path, sizeof(exe_path));
if (count != -1) {
chdir(dirname(exe_path));
}
#endif

bool initialized = false;
eprosima::uxr::Server* server = nullptr;
std::vector<std::string> cl(0);

#ifdef __unix__
if(argc == 2 && (strcmp(argv[1], "-h") == 0 || strcmp(argv[1], "--help") == 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 if(argc >= 3 && strcmp(argv[1], "udp") == 0)
else
{
std::cout << "UDP agent initialization... ";
uint16_t port = parsePort(argv[2]);
eprosima::uxr::UDPServer* udp_server = (argc == 4) //discovery port
? new eprosima::uxr::UDPServer(port, parsePort(argv[3]))
: new eprosima::uxr::UDPServer(port);
if (udp_server->run())
for (int i = 1; i < argc; ++i)
{
initialized = true;
cl.push_back(argv[i]);
}
std::cout << ((!initialized) ? "ERROR" : "OK") << std::endl;
}
else if(argc >= 3 && strcmp(argv[1], "tcp") == 0)

if((1 == cl.size()) && (("-h" == cl[0]) || ("--help" == cl[0])))
{
showHelp();
}
else if((2 <= cl.size()) && ("udp" == cl[0]))
{
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
}
else if((2 <= cl.size()) && ("tcp" == cl[0]))
{
std::cout << "TCP agent initialization... ";
uint16_t port = parsePort(argv[2]);
eprosima::uxr::TCPServer* tcp_server = (argc == 4) //discovery port
? new eprosima::uxr::TCPServer(port, parsePort(argv[3]))
: new eprosima::uxr::TCPServer(port);
if (tcp_server->run())
{
initialized = true;
}
std::cout << ((!initialized) ? "ERROR" : "OK") << std::endl;
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);
#endif
}
else if(argc == 3 && strcmp(argv[1], "serial") == 0)
#ifndef _WIN32
else if((2 == cl.size()) && ("serial" == cl[0]))
{
std::cout << "Serial agent initialization... ";

/* Open serial device. */
int fd = open(argv[2], O_RDWR | O_NOCTTY);
int fd = open(cl[1].c_str(), O_RDWR | O_NOCTTY);
if (0 < fd)
{
struct termios tty_config;
Expand Down Expand Up @@ -181,18 +180,12 @@ int main(int argc, char** argv)

if (0 == tcsetattr(fd, TCSANOW, &tty_config))
{
eprosima::uxr::SerialServer* serial_server = new eprosima::uxr::SerialServer(fd, 0);
if (serial_server->run())
{
initialized = true;
}
server = new eprosima::uxr::SerialServer(fd, 0);
}
}
}

std::cout << ((!initialized) ? "ERROR" : "OK") << std::endl;
}
else if (argc == 2 && strcmp(argv[1], "pseudo-serial") == 0)
else if ((1 == cl.size()) && ("pseudo-serial" == cl[0]))
{
std::cout << "Pseudo-Serial initialization... ";

Expand All @@ -208,78 +201,36 @@ int main(int argc, char** argv)
cfmakeraw(&attr);
tcflush(fd, TCIOFLUSH);
tcsetattr(fd, TCSANOW, &attr);
std::cout << "Device: " << dev << std::endl;
}
}

/* Launch server. */
eprosima::uxr::SerialServer* serial_server = new eprosima::uxr::SerialServer(fd, 0x00);
if (serial_server->run())
{
initialized = true;
}

if (initialized)
{
std::cout << "OK" << std::endl;
std::cout << "Device: " << dev << std::endl;
}
else
{
std::cout << "ERROR" << std::endl;
}
server = new eprosima::uxr::SerialServer(fd, 0x00);
}
#endif
else
{
initializationError();
}
#elif _WIN32
(void) argc;
(void) argv;

std::string server_type = "";
std::cout << "Select server type [udp|tcp]: ";
std::cin >> server_type;

if ("udp" == server_type)
if (nullptr != server)
{
uint16_t port = 0;
std::cout << "Select port: ";
std::cin >> port;

std::cout << "UDP agent initialization.... ";
eprosima::uxr::UDPServer* udp_server = new eprosima::uxr::UDPServer(port);
if (udp_server->run())
/* Launch server. */
if (server->run())
{
initialized = true;
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();
}
std::cout << ((!initialized) ? "ERROR" : "OK") << std::endl;
}
else if ("tcp" == server_type)
{
uint16_t port = 0;
std::cout << "Select port: ";
std::cin >> port;

std::cout << "UDP agent initialization.... ";
eprosima::uxr::TCPServer* tcp_server = new eprosima::uxr::TCPServer(port);
if (tcp_server->run())
else
{
initialized = true;
std::cout << "ERROR" << std::endl;
}
std::cout << ((!initialized) ? "ERROR" : "OK") << std::endl;
}
else
{
std::cout << "Error server type" << std::endl;
}

#endif

if(initialized)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<uros_agent>());
rclcpp::shutdown();
}

return 0;
Expand Down
16 changes: 8 additions & 8 deletions uROS_Agent/uros_agent/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ def GetPackage(Dir):
break


return found_package_path
return found_package_path.replace("\\", "/")


def GetPackageList(Dir):
Expand All @@ -58,7 +58,7 @@ def GetPackageList(Dir):
package_list.append(l)
elif package_path != "COLCON_IGNORE":
package_list.append(package_path)

return package_list


Expand All @@ -70,7 +70,7 @@ def GetInterfacePackages(packages_list):
if element.text == "rosidl_interface_packages":
package_interface_list.append(package)
return package_interface_list


def GetPackageName(package_path):
xml_root = xml.etree.ElementTree.parse(package_path).getroot()
Expand All @@ -88,8 +88,8 @@ def GetInterfacePackageMsgs(package_path):
for file in files:
if file.endswith(".msg"):
full_path = os.path.join(root, file)
msg_list.append(full_path)
msg_list.append(full_path.replace("\\", "/"))

return msg_list

def GetInterfacePackageSrvs(package_path):
Expand All @@ -99,8 +99,8 @@ def GetInterfacePackageSrvs(package_path):
for file in files:
if file.endswith(".srv"):
full_path = os.path.join(root, file)
msg_list.append(full_path)
msg_list.append(full_path.replace("\\", "/"))

return msg_list


Expand All @@ -113,7 +113,7 @@ def ReadDefaultXMLs(Path):
fd = open(full_path)
print ("%s" % fd.read())
fd.close()



def generate_XML(args):
Expand Down