diff --git a/README.md b/README.md index 23352dc98406cd077dbf03206c8e55b29479bc98..1f5347ef5d6bb4b95bab912ccd520bf72e1c9be6 100644 --- a/README.md +++ b/README.md @@ -1,138 +1,106 @@ # iri_ana_how_to -The Ana robot is based on a Pioneer 3 AT platform which has been updated with: +## Description - * A [fanless mini PC i7 computer](http://www.fit-pc.com/web/products/ipc3/) +<details> + <summary>Show more</summary> + + The Ana robot is based on a Pioneer 3 AT platform which has been updated with: + + * A [fanless mini PC i7 computer](http://www.fit-pc.com/web/products/ipc3/) - * Custom 250Wh motor battery from AMOPACK with monitoring electronics. + * Custom 250Wh motor battery from AMOPACK with monitoring electronics. - * Custom 500Wh payload battery from AMOPACK with monitoring electronics. + * Custom 500Wh payload battery from AMOPACK with monitoring electronics. -The expected autonomy of the robot is around 5 hours, and it can operate on its - own with the embedded computer. + The expected autonomy of the robot is around 5 hours, and it can operate on its + own with the embedded computer. -In addition to the standard Pioneer sensors (sonars and bumpers) the Ana robot -provides: + In addition to the standard Pioneer sensors (sonars and bumpers) the Ana robot + provides: - * A low cost IMU sensor [Adafruit BNO055](https://learn.adafruit.com/adafruit-bno055-absolute-orientation-sensor) + * A low cost IMU sensor [Adafruit BNO055](https://learn.adafruit.com/adafruit-bno055-absolute-orientation-sensor) - * A 3d Lidar [Velodyne VLP-16 PUCK](https://velodynelidar.com/vlp-16.html) + * A 3d Lidar [Velodyne VLP-16 PUCK](https://velodynelidar.com/vlp-16.html) - * A depth camera [Intel RealSense D435](https://realsense.intel.com/stereo/) + * A depth camera [Intel RealSense D435](https://realsense.intel.com/stereo/) -All theses sensors are mainly used for navigation and mapping purposes. + All theses sensors are mainly used for navigation and mapping purposes. -The upper part of the robot provides additional sensors and computers to detect -and track people in urban environments. These sensors include: + The upper part of the robot provides additional sensors and computers to detect + and track people in urban environments. These sensors include: - * + * -and are placed on top of a custom pan&tilt platform. + and are placed on top of a custom pan&tilt platform. -A fully featured gazebo model is also provided to test the robot in simulation. + A fully featured gazebo model is also provided to test the robot in simulation. +</details> -# Procedures +## Procedures Here are the basic precedures to use the robot. Please follow them carefully whenever you need to use the robot. - * Startup, operation and shutdown - - * [Battery management](https://gitlab.iri.upc.edu/labrobotica/ros/robots/ana/iri_ana_how_to/-/jobs/artifacts/latex/file/procedures/battery_management/battery_management.pdf?job=latex_to_pdf) - -# How to use the simulated robot + * Startup, operation and shutdown: _pending to generate pdf_ -A Gazebo model for the Ana platform and all its sensors is provided to speed up the testing -process. + * [Battery management](https://gitlab.iri.upc.edu/labrobotica/ros/robots/ana/iri_ana_how_to/-/jobs/artifacts/latex/file/procedures/battery_management/battery_management.pdf?job=latex_to_pdf): _pending fix pdf link_ -To set up the simulator, please follow the next steps: - -Install the following system dependencies: - -``` -sudo apt-get install ros-kinetic-velodyne-description ros-kinetic-velodyne-gazebo-plugins ros-kinetic-hector-gazebo-plugins -``` +## Installation -Install the iri_core dependencies following the instructions in the [iri_ros_how_to](https://gitlab.iri.upc.edu/labrobotica/ros/iri_ros_how_to) repository. +From an existing workspace ([tutorial](http://wiki.ros.org/catkin/Tutorials/create_a_workspace)) + +Merge your workspace with the following rosinstall files following the steps in this [tutorial](http://wiki.ros.org/wstool#Merge_in_Additional_rosinstall_Files). + - Simulation + - [iri_core.rosinstall](https://gitlab.iri.upc.edu/labrobotica/ros/iri_ros_how_to/-/blob/master/rosinstall/iri_core.rosinstall) + - [ana_sim.rosinstall](./rosinstalls/ana_sim.rosinstall) + - Real robot + - [iri_core.rosinstall](https://gitlab.iri.upc.edu/labrobotica/ros/iri_ros_how_to/-/blob/master/rosinstall/iri_core.rosinstall) + - [ana.rosinstall](./rosinstalls/ana.rosinstall) -Install all IRI ros dependencies: - - If you want to use a new ROS workspace: - - * Create a new workspace following the steps in this [tutorial](http://wiki.ros.org/catkin/Tutorials/create_a_workspace). - - * Copy the ana_sim.rosinstall file to the src folder of the new workspace. - - * Initialize the wstool tool on the src folder following the steps in this [tutorial](http://wiki.ros.org/wstool) using - the ana_sim.rosinstall file available on this repository. From the src folder, execute: - -``` -roscd -cd ../src -wstool init ana_sim.rosinstall -``` - - If you want to use an existing ROS workspace: - - * Copy the ana_sim.rosinstall file to the src folder of the existing workspace. - - * Merge the ana_sim.rosinstall file available on this repository with the existing rosinstall file following the steps - in this [tutorial](http://wiki.ros.org/wstool#Merge_in_Additional_rosinstall_Files). From the src folder, execute: +Install dependencies ``` roscd cd ../src -wstool merge ana_sim.rosinstall +rosdep install -r -i --from-paths . ``` -Download the simulator packages by executing the following command from the src folder: - -``` -wstool update -``` +##TODO check if these are defined: +#sudo apt-get install ros-kinetic-velodyne-description ros-kinetic-velodyne-gazebo-plugins ros-kinetic-hector-gazebo-plugins -Compile the newly downloaded packages with the following command: +Compile the workspace ``` +roscd cd .. -catkin_make +catkin_make ``` -Once the setup process is complete, start the simulator with the following command: +## Usage + +### Simulation ``` roslaunch iri_ana_gazebo sim_sample.launch ``` -This command should launch the robot with all its sensors in an empty environment with the RVIZ pre-configured to show all -sensor data. The name and namespace of all topics, services and actions are exactly the same as in the real robot, although -not all of them are available. - -A complete list of all ROS interfaces is shown [here](). - -# How to use the real robot +Default Gazebo world is `empty.world`. -The robot's on-board computer has all the necessary ROS nodes to operate the robot -and it is fully configured. +You can choose a different world specifying the _world_name_ argument with `world_name:=brl`. -IMPORTANT: when using the real robot, make sure you follow all the procedures listed [here]() -to start, operate, shut down and handle the batteries. +See our available worlds in `iri_gazebo_worlds/worlds/*.world` -There are two ways to connect to the robot using an external computer: +### Real robot - * Wireless: the robot creates a hot spot +The robot's on-board computer has all the necessary ROS nodes to operate the robot and it is fully configured. - * Cable: +IMPORTANT: when using the real robot, make sure you follow all the procedures listed above in this file. -Once connected to the same network, configure the external computer following the instructions -in this [tutorial](http://wiki.ros.org/ROS/Tutorials/MultipleMachines). -At this point, you should have acces to all the topic, services and actions provided by the robot. -A complete list of all ROS interfaces is shown [here](). +### What to do next -## What to do next - -All the tutorial included in this section can be used both in simulation or with the real robot. +All the tutorials included in this section can be used both in simulation or with the real robot. * To teleoprate the robot, follow the instructions in this [tutorial](https://gitlab.iri.upc.edu/labrobotica/ros/robots/ana/iri_ana_launch/blob/master/README.md) @@ -140,11 +108,6 @@ All the tutorial included in this section can be used both in simulation or with * To navigate the robot in the new environment, follow the instructions in this tutorial[] -Some tutorials specific to the simulated robot: - - * To change the simulated environment edit the [] file and - # Developers -For advanced users and developers, [here]() there is a more in depth information about the Ana robot -and all its dependencies. +For advanced users and developers, [here]() there is a more in depth information about the robot and its dependencies. diff --git a/rosinstalls/ana.rosinstall b/rosinstalls/ana.rosinstall index d2e508e5da5eb856bd7a3434d4be2149d71a1ad2..d2ca1c3bba8f952fb5092278e734c177621c2c1c 100644 --- a/rosinstalls/ana.rosinstall +++ b/rosinstalls/ana.rosinstall @@ -1,22 +1,5 @@ ###ana_sim.rosinstall ################################## -###iri_core/ -- git: - local-name: iri_core/iri_action_server - uri: ssh://git@gitlab.iri.upc.edu:2202/labrobotica/ros/iri_core/iri_action_server.git -- git: - local-name: iri_core/iri_base_algorithm - uri: ssh://git@gitlab.iri.upc.edu:2202/labrobotica/ros/iri_core/iri_base_algorithm.git - version: kinetic_migration -- git: - local-name: iri_core/iri_base_driver - uri: ssh://git@gitlab.iri.upc.edu:2202/labrobotica/ros/iri_core/iri_base_driver.git - version: kinetic_migration -- git: - local-name: iri_core/iri_ros_tools - uri: ssh://git@gitlab.iri.upc.edu:2202/labrobotica/ros/iri_core/iri_ros_tools.git - version: kinetic_migration -################################## ###navigation/ - git: local-name: navigation/iri_gazebo_worlds @@ -96,4 +79,4 @@ - git: local-name: external/realsense uri: https://github.com/intel-ros/realsense.git -################################## \ No newline at end of file +################################## diff --git a/rosinstalls/ana_sim.rosinstall b/rosinstalls/ana_sim.rosinstall index c4dd6e0b1853214753bc7af78c20232d995b3288..651846420d41e0e4ac9d3d6073748016dacf74c7 100644 --- a/rosinstalls/ana_sim.rosinstall +++ b/rosinstalls/ana_sim.rosinstall @@ -1,22 +1,5 @@ ###ana_sim.rosinstall ################################## -###iri_core/ -- git: - local-name: iri_core/iri_action_server - uri: ssh://git@gitlab.iri.upc.edu:2202/labrobotica/ros/iri_core/iri_action_server.git -- git: - local-name: iri_core/iri_base_algorithm - uri: ssh://git@gitlab.iri.upc.edu:2202/labrobotica/ros/iri_core/iri_base_algorithm.git - version: kinetic_migration -- git: - local-name: iri_core/iri_base_driver - uri: ssh://git@gitlab.iri.upc.edu:2202/labrobotica/ros/iri_core/iri_base_driver.git - version: kinetic_migration -- git: - local-name: iri_core/iri_ros_tools - uri: ssh://git@gitlab.iri.upc.edu:2202/labrobotica/ros/iri_core/iri_ros_tools.git - version: kinetic_migration -################################## ###navigation/ - git: local-name: navigation/iri_gazebo_worlds @@ -87,4 +70,4 @@ - git: local-name: external/realsense uri: https://github.com/intel-ros/realsense.git -################################## \ No newline at end of file +##################################