9 #include "std_msgs/String.h" 10 #include "geometry_msgs/Point32.h" 11 #include "ORCAStar/AgentState.h" 12 #include "ORCAStar/AgentVelocity.h" 13 #include "ORCAStar/Init.h" 19 #ifndef ORCASTAR_ROSMISSION_H 20 #define ORCASTAR_ROSMISSION_H 42 ROSMission(std::string fileName,
size_t agNum,
int threashold = -1,
bool endOnFin =
false);
72 bool InitAgent(ORCAStar::Init::Request &req, ORCAStar::Init::Response &res);
77 unsigned int stepsCount;
78 unsigned int stepsTreshhold;
81 ORCAStar::AgentState agentStateMsg;
83 ros::Publisher ROSMissionPub;
84 ros::Subscriber ROSMissionSub;
89 std::vector<Agent *> agents;
93 std::unordered_map<int, std::pair<bool, int>> resultsLog;
105 #endif //ORCASTAR_ROSMISSION_H Reader class implements base interface for input data reading.
File contains Summary class.
bool PrepareSimulation()
Prepare simulation of multiagen navigation. Read task from XML file. Create ROS service for agent ini...
Class Summary contains brief information about execution results.
File contains Node, Point, Line, Vertex, ObstacleSegment classes and some methods and functions imple...
File contains XMLReader class.
bool InitAgent(ORCAStar::Init::Request &req, ORCAStar::Init::Response &res)
ROSMission(std::string fileName, size_t agNum, int threashold=-1, bool endOnFin=false)
ROSMission constructor with parameters. Initialize multiagent simulation. Creates ROS topics and serv...
Class is an implementation of multiagent navigation ROS module.
void UpdateVelocity(const ORCAStar::AgentVelocity &msg)
void GenerateAgentStateMsg()
Class EnvironmentOptions contains environment and algoritms parameters.
Map class describes static environment.
void StartSimulation()
Start multiagent simulation execution.
~ROSMission()
Default ROSMission destructor.
File contains Agent class and AgentParam class.