Class is an implementation of multiagent navigation ROS module.
More...
#include <ROSMission.h>
Class is an implementation of multiagent navigation ROS module.
Definition at line 28 of file ROSMission.h.
ROSMission::ROSMission |
( |
std::string |
fileName, |
|
|
size_t |
agNum, |
|
|
int |
threashold = -1 , |
|
|
bool |
endOnFin = false |
|
) |
| |
ROSMission constructor with parameters. Initialize multiagent simulation. Creates ROS topics and services.
- Parameters
-
fileName | Path to XML file with multiagent task |
agNum | Number of agents |
threashold | Simulation step threashold (default - no threashold) |
endOnFin | End the simulation when the threshold is reached or when all agents reach their finish positions |
Definition at line 10 of file ROSMission.cpp.
ROSMission::~ROSMission |
( |
| ) |
|
void ROSMission::GenerateAgentStateMsg |
( |
| ) |
|
|
private |
bool ROSMission::InitAgent |
( |
ORCAStar::Init::Request & |
req, |
|
|
ORCAStar::Init::Response & |
res |
|
) |
| |
|
private |
bool ROSMission::IsFinished |
( |
| ) |
|
|
private |
bool ROSMission::PrepareSimulation |
( |
| ) |
|
Prepare simulation of multiagen navigation. Read task from XML file. Create ROS service for agent initialization.
- Returns
- Success of file reading
Definition at line 111 of file ROSMission.cpp.
bool ROSMission::ReadTask |
( |
| ) |
|
|
private |
void ROSMission::StartSimulation |
( |
| ) |
|
Start multiagent simulation execution.
Definition at line 48 of file ROSMission.cpp.
void ROSMission::UpdateState |
( |
| ) |
|
|
private |
void ROSMission::UpdateVelocity |
( |
const ORCAStar::AgentVelocity & |
msg | ) |
|
|
private |
The documentation for this class was generated from the following files: