Skip to content
Gohus edited this page Nov 27, 2018 · 11 revisions

GeRoNa: Generic Robot Navigation

This project contains a set of ROS packages which provide a navigation suite, including path planning on a given map, controlling of the robot to follow this path and obstacle avoidance while driving.

The packages are build with the goal to get a modular, easily extensible framework, where new modules (e.g. kinematic model of a new robot, new collision avoidance algorithms, etc) can be added with minimal effort.

The following video demonstrates various supported robot kinematics:

GeRoNa: Generic Robot Navigation Video

Scientific Details

Theoretical background and experimental results can be found in our recently published GeRoNa paper.

Quick Start

This is only a really quick "quick start" guide. For more detailed explanations, see below.

Send goals from some ROS node

To start the complete navigation project as well as nodes for SLAM and collision detection (using 2d laser), simply run

roslaunch navigation_launch navigation.launch

Now everything is set up and your node can connect to the navigate_to_goal action server and send goals.

Set goals manually using Rviz

If you want to set goal poses manually using Rviz (e.g. for testing or demonstration purposes), run

roslaunch navigation_launch rviz_controlled.launch

Select robot controller/model

By default a controller for car-like robots is used (ackermann_purepursuit). To change this, simply set the environment variable ROBOT_CONTROLLER with the name of the controller you want to use. For example, to use the omni-drive orthexp controller:

export ROBOT_CONTROLLER=omni_orthexp
roslaunch navigation_launch navigation.launch

The controller can also be set via the ROS parameter

rosparam set path_follower/controller_type omni_orthexp

Usage (Simple Interface: The NavigateToGoal Action)

The simplest interface to use the navigation project from outside (e.g. from some high level control node) is completely provided by the path_control_node of the path_control package via the NavigateToGoal (path_msgs/action/NavigateToGoal.action).

The program that wants to move the robot should only communicate with this package and never send any data directly to path_planner or path_follower. path_control manages the communication between them and reports status changes to the high level node.

To use the navigation package make sure at least the following nodes are running:

  • path_control_node of package path_control
  • path_planner_node of package path_planner
  • path_follower_node of package path_follower
  • (optionally) some SLAM algorithm, that provides map and localization (not included in this project)
  • (optionally) an obstacle detection algorithm that publishes a point cloud of obstacle points on the topic /obstacle_cloud.

While not absolutely required, it is strongly recommended to provide a obstacle point cloud for collision avoidance. The simplest way is to use the scan2cloud package of this project that converts laser scans to point clouds, but you can use custom nodes to integrate data of other sources (3D sensors, camera, ...).

All the high level node has to do then, is to set up a SimpleActionClient (see ROS actionlib and connect to the "navigate_to_goal" action server provided by path_control_node. Once the client is set up, goal poses can be send to the path controller. Planning a path to this goal and controlling the robot is all done internally. The high level node is, however, informed of any relevant events via the action feedback messages.

The package path_control contains a node highlevel_dummy_node that can be used as a simple example of how to use the navigation packages (the node receives goal poses on the topic /rviz_goal and sends them to path_control using the action interface).

The following graphic shows the connection between the different nodes.

navigation_package_1

Launch Files

Each of the main packages has one launch file to start its node (with exception of path_follower, which has a separate launch file for each robot controller). Furthermore, there is a package navigation_launch that contains several launch files for nodes that are not included in the navigation project (SLAM, laser filter, ...) as well as a few convenience launch files that simply include the launch files of the other packages to start all at once. The important ones are:

  • navigation.launch: Starts the core of the navigation project. The user has to make sure that external requirements (map, localization) are provided by additional nodes
  • rviz_controlled.launch: Starts navigation.launch and the highlevel_dummy node of path_control. The dummy receives goals from Rviz (set via the "2D Nav Goal" button) and passes them on to the path_control_node using the action interface. Using this launch file is the fastest way to test the navigation process or do some presentation.

Parameters should be managed in a single launch file in navigation_launch. Other launch files should not have to be changed. Please refer to the example launch files.

Select Robot Controller

The path_follower package has a separate launch file for the default parameters of each robot controller, all following the name pattern follower_CONTROLLER_NAME.launch (e.g. follower_ackermann_pid.launch). There is an general file follower.launch which will include all of them. The robot controller is selected via the parameter path_follower/controller_type, which defaults to the environment variable ROBOT_CONTROLLER.

To temporarily select another controller, you can therefore simply set ROBOT_CONTROLLER accordingly before running roslaunch. For example:

export ROBOT_CONTROLLER=omni_orthexp
roslaunch navigation_launch full.launch

This allows you to change the controller without having to modify any launch file.

If ROBOT_CONTROLLER is not set, the controller ackermann_purepursuit is used as default.

Usage (Fine Grained Interface)

Instead of using NavigateToGoal, you can also communicate with the individual subsystems directly. For that, please have a look at the available actions:


Alternatively to the simple NavigateToGoal action

Packages

The main work is done in the packages path_control, path_planner and path_follower. The other packages mostly provide some useful helper nodes.

  • path_control: Controller of the whole process. External nodes should only communicate with path_control and never send anything directly to the planner or follower.
  • path_planner: Plans the path on a given map.
  • path_follower: Controls the robot to drive on the path and tries to avoid obstacles while doing so.
  • path_msgs: Bundles all message types used by the other packages.
  • navigation_launch: Bundles several launch files
  • costmap: A simple costmap generator.
  • roimap: Get a region of interest defined by the boundaries of a known area.
  • scan2cloud: Convert laser scans to point cloud, so it can be used as ObstacleCloud for the collision avoider. If present, scans of front and back laser are combined into one cloud.

Unit Tests

There are some unit test (currently only for path_follower). To run them, go to the root of your catkin workspace and run

catkin_make run_tests