Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 #ifndef COLLVOID_PUBLISHERS_H
00031 #define COLLVOID_PUBLISHERS_H
00032 
00033 
00034 #include <visualization_msgs/Marker.h>
00035 #include <visualization_msgs/MarkerArray.h>
00036 #include "collvoid_local_planner/ROSAgent.h"
00037 
00038 namespace collvoid {
00039 
00040   #define MAX_POINTS_ 400
00041   
00042   void publishHoloSpeed(Vector2 pos, Vector2 vel, std::string base_frame, std::string name_space, ros::Publisher speed_pub);
00043   
00044   void publishVOs(Vector2& pos, const std::vector<VO>& truncated_vos, bool use_truncation, std::string base_frame, std::string name_space, ros::Publisher vo_pub);
00045   
00046   void publishPoints(Vector2& pos, const std::vector<VelocitySample>& points, std::string base_frame, std::string name_space, ros::Publisher samples_pub);
00047   void publishOrcaLines(const std::vector<Line>& orca_lines, Vector2& position, std::string base_frame, std::string name_space, ros::Publisher line_pub);
00048 
00049   void publishObstacleLines(const std::vector<Obstacle>& obstacles_lines, std::string base_frame, std::string name_space, ros::Publisher line_pub);
00050   
00051   void publishMePosition(ROSAgent* me, std::string base_frame, std::string name_space, ros::Publisher me_pub);
00052   void publishNeighborPositions(std::vector<AgentPtr>& neighbors, std::string base_frame, std::string name_space, ros::Publisher neighbors_pub);
00053   
00054   void fillMarkerWithROSAgent(visualization_msgs::MarkerArray& marker, ROSAgent* agent, std::string base_frame, std::string name_space);
00055 
00056 }
00057 
00058 #endif