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" 17 #include "ORCAStar/Init.h" 19 #ifndef ORCASTAR_ROSSIMACTOR_H 20 #define ORCASTAR_ROSSIMACTOR_H 56 bool InitAgent(ORCAStar::Init::Request &req, ORCAStar::Init::Response &res);
63 ORCAStar::AgentVelocity agentVelocityMsg;
64 ORCAStar::ORCAInput inputORCAMsg;
65 ORCAStar::Init::Response initData;
68 ros::Publisher ROSSimActorPub;
69 ros::Subscriber ROSSimActorSub;
71 ros::Publisher ROSSimActorToAgentPub;
72 ros::Subscriber ROSSimActorToAgentSub;
81 #endif //ORCASTAR_ROSSIMACTOR_H The ROSSimActor class is implementation of the intermediate node between the simulation and the agent...
~ROSSimActor()
ROSSimActor destructor.
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.
ROSSimActor()
ROSSimActor default constructor.