Class is an implementation of single agent navigation ROS module based on ORCAStar algorithm. More...
#include <ROSAgent.h>
Public Member Functions | |
void | DoStep (const ORCAStar::ORCAInput &msg) |
ROSAgent ()=default | |
ROSAgent (size_t id) | |
~ROSAgent ()=default | |
Class is an implementation of single agent navigation ROS module based on ORCAStar algorithm.
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 (here) 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.
Definition at line 60 of file ROSAgent.h.
|
default |
ROSAgent default constructor
ROSAgent::ROSAgent | ( | size_t | id | ) |
ROSAgent constructor with agent id. Use this constructor for correct initialization. In this constructor ROS communication objects are created and initial input data is requested.
id | identifier for debug and topics names |
Definition at line 9 of file ROSAgent.cpp.
|
default |
ROSAgent default destructor
void ROSAgent::DoStep | ( | const ORCAStar::ORCAInput & | msg | ) |
The method for calculating the new velocity. Contains the correct start order of the ORCAStar algorithm procedures. ORCAStar algorithm see implemented in ORCAStar Library. This method is called automatically when a message appears in the AgentInput_*agentId* topic.
msg | ORCAStar input data as ROS message |
Definition at line 119 of file ROSAgent.cpp.