ROSMission.h
Go to the documentation of this file.
1 
6 #include <vector>
7 
8 #include "ros/ros.h"
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"
14 #include "Geom.h"
15 #include "XMLReader.h"
16 #include "Agent.h"
17 #include "Summary.h"
18 
19 #ifndef ORCASTAR_ROSMISSION_H
20 #define ORCASTAR_ROSMISSION_H
21 
22 
29 {
30 
31  public:
32 
42  ROSMission(std::string fileName, size_t agNum, int threashold = -1, bool endOnFin = false);
43 
47  ~ROSMission();
48 
56  bool PrepareSimulation();
57 
61  void StartSimulation();
62 
63 
64 
65 
66  private:
67  void GenerateAgentStateMsg();
68  void UpdateVelocity(const ORCAStar::AgentVelocity &msg);
69  void UpdateState();
70  bool IsFinished();
71  bool ReadTask();
72  bool InitAgent(ORCAStar::Init::Request &req, ORCAStar::Init::Response &res);
73 
75  size_t agNumber;
76  size_t agCount;
77  unsigned int stepsCount;
78  unsigned int stepsTreshhold;
79 
80 
81  ORCAStar::AgentState agentStateMsg;
82  ros::NodeHandle n;
83  ros::Publisher ROSMissionPub;
84  ros::Subscriber ROSMissionSub;
85  ros::Rate *loopRate;
86 
87 
88  Reader *taskReader;
89  std::vector<Agent *> agents;
90  EnvironmentOptions *options;
91  Map *map;
92  Summary missionResult;
93  std::unordered_map<int, std::pair<bool, int>> resultsLog;
94  bool initFlag;
95  bool endOnFinish;
96 
98 
99 
100 
101 
102 };
103 
104 
105 #endif //ORCASTAR_ROSMISSION_H
Reader class implements base interface for input data reading.
Definition: Reader.h:21
File contains Summary class.
bool PrepareSimulation()
Prepare simulation of multiagen navigation. Read task from XML file. Create ROS service for agent ini...
Definition: ROSMission.cpp:111
Class Summary contains brief information about execution results.
Definition: Summary.h:32
File contains Node, Point, Line, Vertex, ObstacleSegment classes and some methods and functions imple...
File contains XMLReader class.
bool IsFinished()
Definition: ROSMission.cpp:190
bool InitAgent(ORCAStar::Init::Request &req, ORCAStar::Init::Response &res)
Definition: ROSMission.cpp:146
bool ReadTask()
Definition: ROSMission.cpp:137
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...
Definition: ROSMission.cpp:10
Class is an implementation of multiagent navigation ROS module.
Definition: ROSMission.h:28
void UpdateState()
Definition: ROSMission.cpp:100
void UpdateVelocity(const ORCAStar::AgentVelocity &msg)
Definition: ROSMission.cpp:93
void GenerateAgentStateMsg()
Definition: ROSMission.cpp:72
Class EnvironmentOptions contains environment and algoritms parameters.
Map class describes static environment.
Definition: Map.h:36
void StartSimulation()
Start multiagent simulation execution.
Definition: ROSMission.cpp:48
~ROSMission()
Default ROSMission destructor.
Definition: ROSMission.cpp:40
File contains Agent class and AgentParam class.


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