ORCAAgent.h
Go to the documentation of this file.
1 
6 #include "Agent.h"
7 
8 #ifndef ORCA_ORCAAGENT_H
9 #define ORCA_ORCAAGENT_H
10 
11 
26 class ORCAAgent : public Agent
27 {
28 
29 public:
33  ORCAAgent();
34 
44  ORCAAgent(const int &id, const Point &start, const Point &goal, const Map &map, const EnvironmentOptions &options,
45  AgentParam param);
46 
51  ORCAAgent(const ORCAAgent &obj);
52 
56  ~ORCAAgent();
57 
62  ORCAAgent* Clone() const override;
63 
67  void ComputeNewVelocity() override;
68 
72  void ApplyNewVelocity() override;
73 
78  bool UpdatePrefVelocity() override;
79 
80 
86  bool operator == (const ORCAAgent &another) const;
87 
93  bool operator != (const ORCAAgent &another) const;
94 
100  ORCAAgent &operator = (const ORCAAgent &obj);
101 
102 private:
104  float fakeRadius;
106 };
107 
108 
109 #endif //ORCA_ORCAAGENT_H
bool operator==(const ORCAAgent &another) const
Comparisons operator. Compares id of agents.
Definition: ORCAAgent.cpp:374
void ApplyNewVelocity() override
Method for state updating and appling computed velocity.
Definition: ORCAAgent.cpp:332
ORCAAgent()
ORCAAgent default constructor.
Definition: ORCAAgent.cpp:9
The Point class defines a position (or euclidean vector from (0,0)) in 2D space.
Definition: Geom.h:61
Class AgentParam contains agent and algoritms parameters.
Definition: Agent.h:38
Agent class implements base agent interface and behavior.
Definition: Agent.h:95
bool operator!=(const ORCAAgent &another) const
Comparisons operator. Compares id of agents.
Definition: ORCAAgent.cpp:379
Class EnvironmentOptions contains environment and algoritms parameters.
Map class describes static environment.
Definition: Map.h:36
void ComputeNewVelocity() override
Computes new velocity of agent using ORCA algorithm and linear programing.
Definition: ORCAAgent.cpp:23
ORCAAgent class implements agent with ORCA algoritm behavior.
Definition: ORCAAgent.h:26
ORCAAgent * Clone() const override
Method for cloning objects. Creates copy of object in memmory and return pointer to copy...
Definition: ORCAAgent.cpp:384
File contains Agent class and AgentParam class.
ORCAAgent & operator=(const ORCAAgent &obj)
Assignment operator.
Definition: ORCAAgent.cpp:363
~ORCAAgent()
Virtual destructor.
bool UpdatePrefVelocity() override
Method for computing preffered velocity and chosing current goal from global path.
Definition: ORCAAgent.cpp:338


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