diff --git a/Dockerfile b/Dockerfile index 988fc79..9a32745 100644 --- a/Dockerfile +++ b/Dockerfile @@ -5,6 +5,7 @@ RUN apt-get update && apt-get install -y \ vim \ build-essential \ ros-kinetic-mavros \ + dos2unix \ ros-kinetic-mavros-extras \ ros-kinetic-mavros-msgs \ ros-kinetic-catkin @@ -20,5 +21,6 @@ ENV CATKIN_SETUP_FILE devel/setup.bash RUN apt-get clean COPY ./ros_entrypoint.sh /ros_entrypoint.sh +RUN /bin/bash -c "dos2unix /ros_entrypoint.sh" -HEALTHCHECK --interval=5s --timeout=5s --retries=3 CMD /ros_entrypoint.sh rostopic list \ No newline at end of file +HEALTHCHECK --interval=5s --timeout=5s --retries=3 CMD /ros_entrypoint.sh rostopic list diff --git a/README.md b/README.md index 64a87c8..4fb64d3 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,19 @@ # XbeeMav + + +## Usage + +To run xbee_mav and ros master as a docker pod, use: + - `docker compose -f docker-compose-test-stadalone.yml up --build` + +To run xbee_mav as an exclusive service to flash xbee devices, use: + - `docker compose -f docker-compose-flash-device.yml up --build` + +#### Note: The xbee config file is located in: +- `/xbeemav/Resources/XBee_Config.xml`. +#### This setup assumes the xbee is attached to `/dev/ttyUSB0` and programmed to work at a baud rate of `230400`. + + ## Description The "xbee_ros_node" package provides many tools (ROS nodes) to configure, test and communicate Xbee devices. diff --git a/docker-compose-flash-device.yml b/docker-compose-flash-device.yml new file mode 100644 index 0000000..edc40e5 --- /dev/null +++ b/docker-compose-flash-device.yml @@ -0,0 +1,12 @@ +version: "3.8" + +services: + xbee-mav: + command: rosrun xbee_ros_node xbee_config /dev/ttyUSB0 230400 + build: + context: . + dockerfile: Dockerfile + devices: + - /dev/ttyUSB0:/dev/ttyUSB0 + + diff --git a/docker-compose-test-stadalone.yml b/docker-compose-test-stadalone.yml new file mode 100644 index 0000000..d2d3001 --- /dev/null +++ b/docker-compose-test-stadalone.yml @@ -0,0 +1,45 @@ +version: "3.8" + + + +services: + + ros-master: + image: git.spirirobotics.com/spiri/services-ros1-core:main + command: stdbuf -o L roscore + environment: + - "ROS_MASTER_URI=http://ros-master:11311" + restart: always + ports: + - "11311:11311" + deploy: + resources: + limits: + memory: 1G + # Madness, setting a low ulimit here fixes memory leaks + # https://answers.ros.org/question/336963/rosout-high-memory-usage/ + ulimits: + nofile: + soft: 1024 + hard: 524288 + networks: + - sim_network + + xbee-mav: + # command: rosrun xbee_ros_node xbee_config /dev/ttyUSB0 230400 + command: tail -f /dev/null + depends_on: + - ros-master + build: + context: . + dockerfile: Dockerfile + devices: + - /dev/ttyUSB0:/dev/ttyUSB0 + environment: + - "ROS_MASTER_URI=http://ros-master:11311" + networks: + - sim_network + +networks: + sim_network: + driver: bridge diff --git a/xbeemav/Resources/XBee_Config.xml b/xbeemav/Resources/XBee_Config.xml index e33fdc8..5c1737f 100644 --- a/xbeemav/Resources/XBee_Config.xml +++ b/xbeemav/Resources/XBee_Config.xml @@ -2,9 +2,9 @@ - 00FFFFFFFFFFF7FFFF + 00FFFFFFFFFFFFFFFF 1 - 5FFF + 7777 0 4 A @@ -16,10 +16,10 @@ 0 FFFF C0 - 'Node 1' + Router 82 0 - 11 + 1 0 8 @@ -46,7 +46,7 @@ 1 7FFF 7FFF - 0 + 0 0 0 28 @@ -56,7 +56,7 @@ 0 0 2 - 1 + 1 12C BB8 0 diff --git a/xbeemav/Resources/database.xml b/xbeemav/Resources/database.xml index 26e9faa..ea440c6 100644 --- a/xbeemav/Resources/database.xml +++ b/xbeemav/Resources/database.xml @@ -5,5 +5,7 @@ 0013A20041C4FEAB 0013A20041C4FC1C 0013A20041C4FC97 + 0013A20041C4FF68 + 0013A20041C4FC42 diff --git a/xbeemav/src/XBeeSetup.cpp b/xbeemav/src/XBeeSetup.cpp index f19479b..417e1cd 100644 --- a/xbeemav/src/XBeeSetup.cpp +++ b/xbeemav/src/XBeeSetup.cpp @@ -13,58 +13,41 @@ bool setupXBee(const std::string &device_port, const unsigned int baud_rate) { XBeeModule xbee_module; XMLConfigParser config_parser; - if (xbee_module.Init_Port(device_port, baud_rate)) { - std::thread th_service(&XBeeModule::Run_Service, &xbee_module); - - while (!xbee_module.Is_Connected() && - !xbee_module.Check_Time_Out_Exceeded()) { - continue; - } - - if (xbee_module.Is_Connected()) { - std::cout << "Connected to XBee." << std::endl; - std::cout << "Loading Config File..." << std::endl; - - if (config_parser.Load_Config()) { - std::cout << "Config Loaded Successfully." << std::endl; - std::cout << "Transferring Data..." << std::endl; - std::vector *config_parameters = - config_parser.Get_Loaded_Parameters(); - - for (std::size_t i = 0; i < config_parameters->size(); i++) { - std::string current_command; - xbee_module.Format_AT_Command(config_parameters->at(i), - ¤t_command); - xbee_module.Send_Data(current_command); - } - - std::string write_command = "ATWR \r"; - xbee_module.Send_Data(write_command); - } - } - - th_service.join(); - - std::cout << "Exiting AT Command Mode..." << std::endl; - - if (xbee_module.Is_Connected()) - { - xbee_module.Exit_AT_Command_Mode(); - - if (config_parser.Is_Config_Loaded_Successfully()) - { - std::cout << "XBee Configured Successfully." << std::endl; - return true; - } - else - { - std::cout << "XBee Configuration Failed." << std::endl; - } - } - else - { - std::cout << "XBee Configuration Failed." << std::endl; - } + // Init port at specified baud rate + if (!xbee_module.Init_Port(device_port, baud_rate)) { + std::cout << "XBee Configuration Failed. Could not Init_Port." << std::endl; + return false; } - return false; + + // Run xbee flashing process in a separate thread + std::thread th_service(&XBeeModule::Run_Service, &xbee_module); + + // Wait till connection to device is established + while (!xbee_module.Is_Connected() && !xbee_module.Check_Time_Out_Exceeded()) { + continue; + } + + // Load external config file + if (!config_parser.Load_Config()) { + std::cout << "XBee Configuration Failed. Could not config file." << std::endl; + return false; + } + + // Flash config params to device + std::cout << "Connected to XBee. Flashing Config File..." << std::endl; + std::vector *config_parameters = config_parser.Get_Loaded_Parameters(); + for (auto& param : *config_parameters) { + std::string current_command = ""; + xbee_module.Format_AT_Command(param, ¤t_command); + xbee_module.Send_Data(current_command); + } + std::string write_command = "ATWR \r"; + xbee_module.Send_Data(write_command); + + // Kill service once device has been flashed + th_service.join(); + xbee_module.Exit_AT_Command_Mode(); + + std::cout << "Flashing process complete." << std::endl; + return true; } diff --git a/xbeemav/src/main.cpp b/xbeemav/src/main.cpp index fc6a1b1..1302cf2 100644 --- a/xbeemav/src/main.cpp +++ b/xbeemav/src/main.cpp @@ -13,7 +13,7 @@ int main(int argc, char*argv[]) { std::string device_port; unsigned int baud_rate = 0; - const unsigned int DEFAULT_BAUD_RATE = 9600; + const unsigned int DEFAULT_BAUD_RATE = 230400; const std::string DEFAULT_DEVICE_PORT = "/dev/ttyUSB0"; if (argc < 1) @@ -26,7 +26,7 @@ int main(int argc, char*argv[]) else sscanf(argv[2], "%u", &baud_rate); - //setupXBee(device_port, baud_rate); + setupXBee(device_port, baud_rate); } catch (const std::exception& e) {