-
Notifications
You must be signed in to change notification settings - Fork 0
Understanding the code base
Autonomous navigation in practice is typically complex, especially if the navigation infrastructure is designed to be run across multiple robots - as is the case in ROS. This page aims to give a brief explanation of navigation with relevant links.
- Sensors, actuators and a computing platform! The ability to use the computing platform to get sensor data and analyze it, and the ability to use the computing platform to send commands to actuators.
- An environment to navigate in (can be real real-world or simulation).
- An understanding of where sensors are on the robot body - A sensor facing forward needs to be treated differently from a sensor facing backwards!
When running in simulation, the real world is simulated through the 3D Gazebo simulator. Gazebo has excellent integration with ROS through the gazebo_ros_pkgs ROS package. A number of plugins representing sensors and displays in the real world are available in the gazebo_plugins package.
In the real world, the robot needs to load the hardware drivers for the segway base and all sensors. These drivers should have appropriate ROS interfaces for the rest of the system to interact with it. All of the top-level launch files for sensors are located in the segbot_sensors package. The top-level launch file for running the segway driver is located in the segbot_bringup package, and these launch files make use of launch files in segbot_sensors as needed.
Inside simulation, select plugins from gazebo_plugins are loaded instead of their real-world counterparts. This includes a differential drive plugin for the segway base, and appropriate laser, kinect and camera plugins for the sensors.
Inside segbot_bringup, all the files in the launch
folder are directly run on the hardware, and launch/includes
contains all components common between the real world and simulation. The common components include things like a description of where the sensors are on the robot, as well as any processing filters we apply on sensor data. One example of a processing filter is removing any points from the laser sensor that are on the body of the robot itself (see footprint_filter).
All the remaining portions of the code are completely unaware about the fact as to whether the robot is running in the real world or in simulation, and run in exactly the same manner. One minor exception to this is the robot description, which in simulation also tells Gazebo where to spawn specific sensors on the robot's body.
A full description of the robot details the location of all moving or static joints of the robot. A robot can be described using an XML description format, and in ROS a format called URDF is used. A ROS node (see robot_state_publisher) reads this URDF description and produces transforms for all the fixed joints. Transforms are a standard way of describing simple joints and linkages, and in ROS the implementation is called tf.
Note that a robot can be fairly complex with many repeated parts. This can make the xml extremely long and with a fair amount of redundancy. In the ROS ecosystem, this redundancy is removed by a pre-processor called xacro, which allows for basic math, conditional statements and macro expansions to automatically generate the XML from a smaller set of XML descriptions.
Additionally, in the case of simulation, Gazebo needs to know where to spawn sensors and with what parameters. This is accomplished by gazebo specific tags inside the URDF description. These tags are documented on the Gazebo wiki.
For our differential drive robots, any moving joints are not important. For this reason we do not attempt to publish real joint values, and simply publish zeros for all moving joints. This is accomplished through joint_state_publisher.
- The tf tree for our robot is pretty big, so that the robot in simulation roughly looks equivalent to the real robot. An example of one such description is the configuration file we typically use for navigation (that uses both a Hokuyo and a Segbot):
- Each link in the description has inertial (gazebo), visual (rviz, gazebo), collision (gazebo) components. The software in parenthesis indicates whether it uses that particular piece of information.
- To see the full description of the robot (generated using xacro):
rosrun xacro xacro `rospack find segbot_description`/robots/segbot_navigation.urdf.xacro use_full_gazebo_model:=false > test
- Setting use_full_gazebo_model to true uses the true shape of the object in the collision model during simulation, and consequently the simulation is much more computationally intensive. Setting the parameter to false remove collision models from all elements in the robot, and only base_link (the robot's torso) has a box collision model. This simpler collision model gives an order of magnitude speedup inside Gazebo. Note that this feature is used only in simulation (and visualization and real world operation remain unaffected).
Given all these pieces of information, it is possible to run the robot such that higher-level applications such as autonomous navigation can be written to use the robot.
- A map of the world (or the ability to construct this map on the fly).
- The robot's position inside the map.
- A global planner that finds an approximate route to the destination
- A local navigator that attempts to execute the global plan while avoiding obstacles
A 2D map in the ROS ecosystem is defined by an image file (PGM) describing map occupancy, and a description file (YAML) that contains information such as the resolution of the image, and the location of the world origin on the image.
These maps are published into the ROS Ecosystem by the map_server. Some maps for the building are available for view at: http://farnsworth.csres.utexas.edu/maps/
Localization is performed using Adaptive Monte Carlo Localization (aka Particle Filters). Check out the amcl package. The implementation is based from notes in the Probabilistic Robotics book. A number of people in the lab have a copy of the book.
Instead of running the map server + localization, you can try and build a map of the world as you go through a SLAM approach. Check out the gmapping package.
In practice, gmapping is used with tele-operation to build a map of the world first. Using gmapping with autonomous navigation will probably not work, and the robot will most likely not create a good map, and will be unable to localize or navigate successfully.
To understand how the ROS Navigation stack is used by a Segbot to autonomously navigate, first take a look at the Robot Setup tutorial for the navigation stack.
- We use a global planner called navfn (which internally uses an implementation of Dijkstra's or AStar to find the shorted path) to produce a path from the current location to the goal. All global planners are plugins created using base_global_planner as the base class.
- The robot follows the global path produced by the global planner using a local planner. The default local planner used inside ROS is called dwa_local_planner which uses the dynamic window approach to navigation. We use eband_local_planner approach for navigation. The video on the the eband_local_planner approach is old, but does a decent job at explaining the idea behind the approach. The page also lists the research page on which this navigation approach is based.
- Costmaps are used to track obstacles inside ROS. Global costmaps are used by the global planner to plan the global path, and these costmaps are in the frame of reference of the map.
- Local costmaps is an independent estimate of obstacles around the robot, and is different from the global costmap as it is in the frame of reference of the robot itself. What this means is that if localization jumps the robot to a different location, obstacles in the local costmap jump with the robot, whereas obstacles in the global costmap stay put. At this time, it is unclear if we need to have separate estimates of these two costmaps, as we don't jump too frequently, and we have enough sensors on the robot to re-detect any obstacles even if they don't jump with us. The eband approach will work better with a single costmap, as it tries to combine local planning with global planning.
-
Layered costmaps were introduces in ROS Hydro. The idea behind layers is that obstacles detected in one layer are not affected by obstacles in another layer. This is useful as glass walls provided in the map are typically not visible by sensors, and these obstacles should not be cleared from the map. There are 4 layers by default:
- Static Layer - Built from map from map_server. Cannot be changed by sensor data.
- Obstacle Layer - From sensor data (hokuyo, kinect). If we add sonars and IRs, we'll need 2 obstacles layers because they will have conflicting information (as sonars see glass walls and metallic surfaces, and cliff IRS see dropoffs, both of which are not visible by other sensors).
- Footprint layer - removes obstacles in the footprint of the robot.
- Inflation layer - inflates all obstacles by the radius of the robot, so that we can assume the robot to be a point for navigation purposes. This is an approximation for non-circular robots.
All the parameters that we use for localization are stored in segbot_apps/segbot_navigation/config/eband
.
We use a particle filter for determining the robot's location in the environment, which is called amcl in the ROS ecosystem. The parameters used for localization are currently stored in the launch file directly. See amcl.launch
in segbot_navigation
.
- The robot driver publishes a tf transformation from
odom -> base_footprint
. amcl publishes a correction frommap -> odom
to give estimated position of the robot in the map frame. - All tf names such as map, odom, base_footprint are frame_ids. In ROS, there is a message called std_msgs/Header (timestamp + frame_id). Any message that is called a stamped message will have a header
message inside it.. Any sensor data will be stamped - it will have a timestamp, as well a frame id.
- Starting with hydro, frame_ids do not have a starting /
This section looks at one of the top-level launch files used to run navigation inside the simulator. segbot_navigation.launch
is a top-level roslaunch file that includes the following pieces:
- Create the Gazebo server + GUI with a 3D world:
roslaunch segbot_gazebo segbot_test_world.launch
- Creates the TF trasform of the robot in gazebo (3D view)
- Tells the simulator where the sensors are with repect to eachother
- This also runs the urdf files and joint state files
roslaunch segbot_gazebo segbot_mobile_base.launch
- Adds a 2d map file that should mirror the 3D map gazebo is using
- Needed by AMCL
roslaunch segbot_gazebo bwi_test_world_map_server.launch
- This is an bubble based point A to B directions planner
- It creates “bubbles” in its path from point A to B
- The bigger the bubble the faster the robot is allowed to move
- Bubble size is constrained by obstacles
roslaunch segbot_navigation move_base_eband.launch
- Does localization using a supplied map
roslaunch segbot_navigation amcl.launch
- Shows you what the robot is seeing rather than what the “simulated real world” of gazebo is showing you
roslaunch segbot_navigation rviz.launch