Agent.h
Go to the documentation of this file.
1 
17 #include "Const.h"
18 #include "PathPlanner.h"
19 #include "ThetaStar.h"
20 #include "Geom.h"
21 
22 #include <vector>
23 #include <cmath>
24 #include <algorithm>
25 #include <iostream>
26 #include <type_traits>
27 #include <cstddef>
28 
29 #ifndef ORCA_AGENT_H
30 #define ORCA_AGENT_H
31 
32 
39 {
40  public:
53 
64  AgentParam(float sr, float tb, float tbo, float r, float reps, float ms, int amn) : sightRadius(sr), timeBoundary(tb), timeBoundaryObst(tbo), radius(r), rEps(reps),
65  maxSpeed(ms), agentsMaxNum(amn) {}
66 
70  ~AgentParam() = default;
71 
72  float sightRadius;
73  float timeBoundary;
75  float radius;
76  float rEps;
77  float maxSpeed;
79 };
80 
81 
95 class Agent
96 {
97 
98 
99  public:
103  Agent();
104 
114  Agent(const int &id, const Point &start, const Point &goal, const Map &map, const EnvironmentOptions &options, AgentParam param);
115 
120  Agent(const Agent &obj);
121 
125  virtual ~Agent();
126 
131  virtual Agent* Clone() const = 0;
132 
136  virtual void ComputeNewVelocity() = 0;
137 
138 
142  virtual void ApplyNewVelocity() = 0;
143 
148  virtual bool UpdatePrefVelocity() = 0;
149 
150 
155  virtual void SetPosition(const Point &pos);
156 
162  virtual void AddNeighbour(Agent &neighbour, float distSq);
163 
168  virtual bool isFinished();
169 
174  virtual void SetVelocity(const Point &vel);
175 
180  bool InitPath();
181 
186  int GetID() const;
187 
192  Point GetPosition() const;
193 
198  Point GetVelocity() const;
199 
200 
205  float GetRadius() const;
206 
211  Point GetNext() const;
212 
217  Point GetStart() const;
218 
223  Point GetGoal() const;
224 
229  AgentParam GetParam() const;
230 
235  std::pair<unsigned int, unsigned int> GetCollision() const;
236 
240  void UpdateNeighbourObst();
241 
247  bool operator == (const Agent &another) const;
248 
254  bool operator != (const Agent &another) const;
255 
261  Agent & operator = (const Agent& obj);
262 
267  template <class Planner> void SetPlanner(const Planner &pl)
268  {
269  static_assert(std::is_base_of<PathPlanner, Planner>::value, "Planner should be inheritor of PathPlanner");
270  this->planner = new Planner(pl);
271  }
272 
273 
274  protected:
275 
277  int id;
278  Point start;
279  Point goal;
280  PathPlanner *planner;
281  const EnvironmentOptions *options;
282  const Map *map;
283  std::vector <std::pair<float, Agent*>> Neighbours;
284  std::vector <std::pair<float, ObstacleSegment>> NeighboursObst;
285 
286  std::vector <Line> ORCALines;
287 
288  Point position;
289  Velocity prefV;
290  Velocity newV;
291  Velocity currV;
292 
293  AgentParam param;
294  float invTimeBoundaryObst;
295  float invTimeBoundary;
296  float maxSqObstDist;
297 
298  unsigned int collisions;
299  unsigned int collisionsObst;
300 
301  Point nextForLog;
303 };
304 
305 
306 
307 
308 
309 #endif //ORCA_AGENT_H
#define CN_DEFAULT_AGENTS_MAX_NUM
Default agent max neighbours number value.
Definition: Const.h:116
PathPlanner class implements base pathfinder interface and behavior.
Definition: PathPlanner.h:25
float sightRadius
Radius in which the agent takes neighbors into account.
Definition: Agent.h:72
float radius
Size of the agent (radius of the agent).
Definition: Agent.h:75
AgentParam(float sr, float tb, float tbo, float r, float reps, float ms, int amn)
AgentParam constructor with parameters.
Definition: Agent.h:64
File contains Node, Point, Line, Vertex, ObstacleSegment classes and some methods and functions imple...
float rEps
Buffer size (more about buffer see Main page).
Definition: Agent.h:76
The Point class defines a position (or euclidean vector from (0,0)) in 2D space.
Definition: Geom.h:61
float timeBoundaryObst
Time within which ORCA algorithm ensures collision avoidance with neighbor obstacles.
Definition: Agent.h:74
int agentsMaxNum
Number of neighbors, that the agent takes into account.
Definition: Agent.h:78
void SetPlanner(const Planner &pl)
Set global planner object.
Definition: Agent.h:267
#define CN_DEFAULT_REPS
Default agent buffer size value.
Definition: Const.h:127
File contains ThetaStar class.
Class AgentParam contains agent and algoritms parameters.
Definition: Agent.h:38
#define CN_DEFAULT_RADIUS_OF_SIGHT
Default agent radius of sight value.
Definition: Const.h:119
#define CN_DEFAULT_TIME_BOUNDARY
Default ORCA time boundary value.
Definition: Const.h:117
File contains PathPlanner class.
Agent class implements base agent interface and behavior.
Definition: Agent.h:95
~AgentParam()=default
AgentParam default destructor.
float timeBoundary
Time within which ORCA algorithm ensures collision avoidance with neighbor agents.
Definition: Agent.h:73
#define CN_DEFAULT_MAX_SPEED
Default agent max speed value.
Definition: Const.h:115
#define CN_DEFAULT_OBS_TIME_BOUNDARY
Default ORCA time boundary for obstacles value.
Definition: Const.h:118
Class EnvironmentOptions contains environment and algoritms parameters.
Map class describes static environment.
Definition: Map.h:36
float maxSpeed
Maximum speed of agent.
Definition: Agent.h:77
File contains main constants.
#define CN_DEFAULT_SIZE
Default agent size value.
Definition: Const.h:114
#define Velocity
Velocity type definition.
Definition: Const.h:10
AgentParam()
AgentParam default constructor.
Definition: Agent.h:51


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