ROSSimActor.h
Go to the documentation of this file.
1 
7 #include <vector>
8 #include <sstream>
9 
10 #include "ros/ros.h"
11 #include "std_msgs/String.h"
12 #include "geometry_msgs/Point32.h"
13 #include "ORCAStar/AgentState.h"
14 #include "ORCAStar/AgentVelocity.h"
15 #include "ORCAStar/ORCAInput.h"
16 #include "Geom.h"
17 #include "ORCAStar/Init.h"
18 
19 #ifndef ORCASTAR_ROSSIMACTOR_H
20 #define ORCASTAR_ROSSIMACTOR_H
21 
27 {
28  public:
32  ROSSimActor();
33 
37  ~ROSSimActor();
38 
43  void ReceiveAgentStates(const ORCAStar::AgentState &msg);
44 
49  void TransmitAgentVelocity(const geometry_msgs::Point32 &msg);
50 
51 
52 
53  private:
54 
56  bool InitAgent(ORCAStar::Init::Request &req, ORCAStar::Init::Response &res);
57 
58 
59  size_t id;
60  size_t agNumber ;
61  float sightRad;
62 
63  ORCAStar::AgentVelocity agentVelocityMsg;
64  ORCAStar::ORCAInput inputORCAMsg;
65  ORCAStar::Init::Response initData;
66 
67  ros::NodeHandle n;
68  ros::Publisher ROSSimActorPub;
69  ros::Subscriber ROSSimActorSub;
70 
71  ros::Publisher ROSSimActorToAgentPub;
72  ros::Subscriber ROSSimActorToAgentSub;
73 
74  bool initFlag;
75 
77 };
78 
79 
80 
81 #endif //ORCASTAR_ROSSIMACTOR_H
The ROSSimActor class is implementation of the intermediate node between the simulation and the agent...
Definition: ROSSimActor.h:26
~ROSSimActor()
ROSSimActor destructor.
Definition: ROSSimActor.cpp:68
File contains Node, Point, Line, Vertex, ObstacleSegment classes and some methods and functions imple...
void TransmitAgentVelocity(const geometry_msgs::Point32 &msg)
Receives computed velocity from agent module and transmits it to simulation module.
void ReceiveAgentStates(const ORCAStar::AgentState &msg)
Receives all agents states and transmits neighbours states to single agent module.
Definition: ROSSimActor.cpp:72
ROSSimActor()
ROSSimActor default constructor.
Definition: ROSSimActor.cpp:9


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