ORCA* ROS

Decentralized navigation system based on ORCA and Theta* algorithms and implemented as ROS nodes

ORCA* Algorithm

Description

The algorithm is based on the idea of planning a global path for all agents independently and moving along this path with local collision avoidance. Theta* algorithm are using to global path planning and ORCA algorithm are using for local collision avoidance with agents and static obstacles. Also direct moving to goal without global planning is available.

Theta* is a version of A* algorithm for any-angle path planning on grids. Theta* mostly the same as A*, but, unlike A*, Theta* allows parent of current vertex may be any other vertex, which are visible from current [1].

The ORCA algorithm is a decentralized collision avoidance algorithm in a multi-agent environment. The main idea of ​​the algorithm is iterative selection of new agent speed, close to a certain preferred velocity. Selection of the new speed is based on ORCA principle. Optimal Reciprocal Collision Avoidance (ORCA) — the principle, which provides a sufficient condition for multiple robots to avoid collisions among one another, and thus can guarantee collision-free navigation [2]. The principle is based on the concept of velocity obstacles, which are used to search for a new speed of agent so that during the time t there is no collision with other agents. In the process of searching for a new velocity, algorithm creates a set of n-1 linear constraints(where n is the number of agents that the current one takes into account). A new velocity (Vnew) that satisfies these constraints and is close to the preferred velocity, are searched using an linear programming. The preferred velocity is selected so that the agent makes a move to the target point. More information about ORCA algorithm you can find at ORCA creators web page [3].

The agent is a disk of radius r with buffer radius ε centered at p with their start and global goal positions.

Agent sheme

For each neighboring agent (located at a distance R or less), their position and current speed are known. At the beginning of task execution every agent tries to find a path to their global goal, using Theta* algorithm. After getting of global path (which is a sequence of points in space, where the first point is the global goal), agent begin moving. First target point is the last element in path sequence. At each simulation step, for each agent, a new velocity Vnew are searched, using ORCA algorithm. After that global simulation time is changed to dt, the position of all agents is changed to dt * Vnew (own for each agent) and every agent compute new target point. If the agent has reached the last point in the sequence, then the next point in the sequence becomes the target, and the previous one is deleted. Otherwise, a visibility check is made between the agent’s position and the last point. If visibility is confirmed, then the last becomes the target point, otherwise the path from the agent's position to the last point is searched.

Block scheme of the algorithm is shown in the figures below.

Algorithm block sheme

The implementation of ORCA* algorithm located in ./ORCAStarLib/ subdirectory. It based on [4]. Implementation relies only on C++11 standard and STL. I/O modules use open-source library tinyXML to work with XML. It is included at the source level (i.e. .h and .cpp files are part of the project) in ./ORCAStarLib/tinyxml/ subdirectory. Full documentation for ORCA* implementation source code located here.

ROS Imlemetation

Requirements

To build and run ORCA* ROS you nedd the following software:

Tested on the following configuration:

Map sheme

Installing

Download current repository to your local machine. Use

1 git clone https://github.com/PathPlanning/ORCAStarROS.git

or direct downloading.

Add installation path to ROS_PACKAGE_PATH variable

1 export ROS_PACKAGE_PATH=*installation path*:$ROS_PACKAGE_PATH

Build

Go to the directory with ORCAStar using teminal.

1 roscd ORCAStarROS

Start building process using rosmake

1 rosmake .

Run Tests

Tests use gtest library, which is included to ROS. To build tests run following command:

1 make test

To run tests run commands:

1 cd bin/test
2 ./ORCAStarTest

Single Agent

The main part in a navigation system is the single agent navigation module. This component can be used both for embedding a separate robot and for centralized calculation of trajectories, but using distributed computing. The single agent navigation implemented as a ROS node. The node operation is divided into 2 stages.

At the first stage, node is initialized, the algorithms parameters and static environment data are requested from ROS services, global path is created. The node sends a request to service initAgentServer_*id*(Service description: here, id is identifier of agent, which sets as ROS private parameter) and awaits a response. For using ROS Agent node you should launch such service. After that, the node sends a request to the service static_map of map_server node. You should launch this node before launching ROS Agent node.

At the second stage the process of following the global path starts. The node waits for messages in topic AgentInput_*id*. After a message with input data (msg description) appears in the topic AgentInput_*id*, new velocity computation procedure starts. New velocity publishes in the topic AgentOutput_*id* (in geometry_msgs::Point32 format). The second stage continues until the node is working. An illustration of the operation of the node is presented in the figure below.

Map sheme

Launch

To launch single agent ROS node rosrun util can be used.

1 rosrun ORCAStar ROSAgent _id:=0

Roslaunch files also can be used.

1 <node name="$(anon ROSAgent_0)" pkg="ORCAStar" type="ROSAgent">
2  <param name="id" type="int" value="0"/>
3 </node>

If you are launching a single instance of the node, then use parameter id equal to any integer (0 for example). When running multiple instances, use unique values.

I/O Format

As input and output uses following ROS services and topics:

Map Format

The map is set in the form of a grid, are also described in the form of polygons. The grid is a rectangular matrix of square cells, each cell can be traversable or not. The size of cell side is variable. The address of each cell on the grid is specified by a pair (i, j), where i is the row number of the matrix, j is the column number of the matrix. The environment description is specified in the orthogonal coordinates. Every obstacle in form of polygon is vector of points in orthogonal coordinates. Vertices of the simple obstacle shold be listed in counterclockwise order, vertices of boundary in clockwise order. An illustration of the environment is presented in the figure below.

Map sheme

Multiple Agents

Based on the autonomous navigation module of a single agent, a simple simulation of the work of a group of agents was built. These modules can be used to verify the operation of the navigation system or as an example of using a single agent module.

System includes the following modules. The main module (ROSMission) is responsible for storing, updating and transmitting data about the state of the entire system. Intermediate module (ROSSimActor) is responsible for the interaction between the main module and the single agent navigation module. A navigation module for a single agent (ROSAgent). In addition, the system uses a standard ROS node that provides environmental information on request in the format of a grid ([6]).

At the initial stage of operation, the ROSMission node reads information on the agents parameters, start and end positions, as well as data on static obstacles from an XML file, the path to which is specified in the format of the private ROS parameter. After that, agents are registered in ROSMission. The main module creates the initialization service and expects the required number of requests (equal to the number of agents), in response to each request, the identifier of the new registered participant in the system, data on the initial and final position of the new agent, agent parameters and data on the static environment are transmitted. When the required number of agents has been registered, the central module creates a topic where the states of all agents are published at discrete time steps. In addition, the central module subscribes to the topic where the results of calculating the new velocities of each agent are published. After the preparatory operations are completed, a cyclic process is started, consisting of publishing the states of agents, obtaining speeds, updating the status of agents. The period of operation of one iteration of the cycle is constant, i.e. new iterations are launched at regular intervals.

During the initial stage, every ROSSimActor node sends a request to the central module to register a new participant in the system and obtain the necessary input data for a specific agent. Then, in a similar way, the ROSAgent navigation module is initialized (a ROSSimActor node creates a service waiting for a request from a ROSAgent node). The navigation module also requests information about static obstacles in the format of a grid from the map_server node. Every ROSSimActor node subscribes to a topic containing the states of all agents and registers as a publisher in a topic that accepts all computed agent velocities. In addition, two-way communication is creating using topics between the intermediate module and the single agent navigation module.

After the initial stage is completed, the ROSSimActor nodes wait publication of data on the current state of all agents, then every ROSSimActor node selects the neighbors of the specific agent. An input message is generated for ROSAgent node. The ROSAgent nodes receive input, compute the velocity, and pass velocities back to the ROSSimActor nodes. An illustration of nodes with ROS themes for a system of 5 agents is presented in the figure below.

Map sheme

Launch

To launch ROS Mission it is recommended to use roslaunch. The following nodes must be started:

Python script ./scripts/generate.py can be used for generating launch files from XML task files.

Example of launch file is presented below and in ./examples/ subdirectory.

1 <launch>
2  <node name="map_server" pkg="map_server" type="map_server" args="/home/User/ORCAStar/examples/0_task.yml"/>
3 
4 
5  <node name="ROSMission" pkg="ORCAStar" type="ROSMission" output="screen">
6  <param name="agents_number" type="int" value="5"/>
7  <param name="task" type="string" value="/home/User/ORCAStar/examples/0_task.xml"/>
8  <param name="threshhold" type="int" value="1000"/>
9  <param name="end" type="bool" value="False"/>
10  </node>
11 
12  <node name="$(anon ROSSimActor_0)" pkg="ORCAStar" type="ROSSimActor"/>
13  <node name="$(anon ROSAgent_0)" pkg="ORCAStar" type="ROSAgent">
14  <param name="id" type="int" value="0"/>
15  </node>
16 
17  <node name="$(anon ROSSimActor_1)" pkg="ORCAStar" type="ROSSimActor"/>
18  <node name="$(anon ROSAgent_1)" pkg="ORCAStar" type="ROSAgent">
19  <param name="id" type="int" value="1"/>
20  </node>
21 
22  <node name="$(anon ROSSimActor_2)" pkg="ORCAStar" type="ROSSimActor"/>
23  <node name="$(anon ROSAgent_2)" pkg="ORCAStar" type="ROSAgent">
24  <param name="id" type="int" value="2"/>
25  </node>
26 
27  <node name="$(anon ROSSimActor_3)" pkg="ORCAStar" type="ROSSimActor"/>
28  <node name="$(anon ROSAgent_3)" pkg="ORCAStar" type="ROSAgent">
29  <param name="id" type="int" value="3"/>
30  </node>
31 
32  <node name="$(anon ROSSimActor_4)" pkg="ORCAStar" type="ROSSimActor"/>
33  <node name="$(anon ROSAgent_4)" pkg="ORCAStar" type="ROSAgent">
34  <param name="id" type="int" value="4"/>
35  </node>
36 
37  <node name="rviz" pkg="rviz" type="rviz"/>
38  <node name="ROSVisualization" pkg="ORCAStar" type="ROSVisualization"/>
39 </launch>

I/O Format

Input files are an XML files with a specific structure. Map format is the same as for single agent. Example of XML files are presented in ./examples/ subdirectory. Input file should contain:

Output of simulation is made to topic AgentStates using message format AgentState. It includes positions, velocities and sizes of all agent on current step.

Visualisation

The simulation visualized using rviz. To use visualization add floowing nodes to the launch file. Examples of rviz config files are presented in ./examples/ subdirectory.

1 <node name="rviz" pkg="rviz" type="rviz"/>
2 <node name="ROSVisualization" pkg="ORCAStar" type="ROSVisualization"/>

Example of visualized simulation is presented below.

vis

Source Code Documentation

Full source code documentation is presented here.

Documentation for ROS messages and services is presented here

Links

  1. Daniel K. et al. Theta*: Any-angle path planning on grids // Journal of Artificial Intelligence Research. – 2010. – vol. 39. – p. 533-579.
  2. Van Den Berg J. et al. Reciprocal n-body collision avoidance // Robotics research. – Springer, Berlin, Heidelberg, 2011. – p. 3-19.
  3. ORCA creators webpage
  4. ORCA* algoritm implementation
  5. ROS Kinetic installation instructions
  6. map_server node description


ORCAStar
Author(s): Stepan Drgachev
autogenerated on Wed Jul 15 2020 16:13:14