 |
Multi-robot Playground
|
Go to the documentation of this file.
53 #include "nav_msgs/OccupancyGrid.h"
54 #include "geometry_msgs/Point.h"
55 #include "geometry_msgs/PoseArray.h"
56 #include "std_msgs/String.h"
57 #include "multirobotsimulations/CustomPose.h"
58 #include "multirobotsimulations/Frontiers.h"
59 #include "visualization_msgs/Marker.h"
60 #include "visualization_msgs/MarkerArray.h"
90 void CreateMarker(visualization_msgs::Marker& input,
const char* ns,
const int&
id,
const int& seq);
91 void SetPoseArr(geometry_msgs::PoseArray& arr,
const int& seq);
void SetPoseArr(geometry_msgs::PoseArray &arr, const int &seq)
double ComputeCentroidValue(nav_msgs::OccupancyGrid &occ, Vec2i ¢roid, const double &lidarRange)
double aMaxLidarRange
Definition: FrontierDiscoveryNode.h:106
ros::Publisher aClusterMarkerPub
Definition: FrontierDiscoveryNode.h:124
double aRate
Definition: FrontierDiscoveryNode.h:104
@ IDLE
Definition: FrontierDiscoveryNode.h:72
Definition: FrontierDiscoveryNode.h:80
int aQueueSize
Definition: FrontierDiscoveryNode.h:98
FrontierState aState
Definition: FrontierDiscoveryNode.h:108
int aSeq
Definition: FrontierDiscoveryNode.h:100
void CreateMarker(visualization_msgs::Marker &input, const char *ns, const int &id, const int &seq)
std::vector< Vec2i > aFrontiers
Definition: FrontierDiscoveryNode.h:142
std::vector< ros::Timer > aTimers
Definition: FrontierDiscoveryNode.h:114
std::list< Vec2i > aPath
Definition: FrontierDiscoveryNode.h:141
@ FINISHED
Definition: FrontierDiscoveryNode.h:74
void EstimatePoseCallback(multirobotsimulations::CustomPose::ConstPtr msg)
visualization_msgs::Marker aClusterMarkerMsg
Definition: FrontierDiscoveryNode.h:136
multirobotsimulations::Frontiers aFrontierMsg
Definition: FrontierDiscoveryNode.h:131
bool aReceivedCSpace
Definition: FrontierDiscoveryNode.h:102
int aClusterDetectionMin
Definition: FrontierDiscoveryNode.h:101
@ PROCESSING
Definition: FrontierDiscoveryNode.h:73
geometry_msgs::Pose aWorldPos
Definition: FrontierDiscoveryNode.h:133
ros::Publisher aFrontiersMapPub
Definition: FrontierDiscoveryNode.h:125
Vec2i aPos
Definition: FrontierDiscoveryNode.h:107
std::vector< Vec2i > aCentroids
Definition: FrontierDiscoveryNode.h:143
void ComputeCallback(std_msgs::String::ConstPtr msg)
FrontierState
Definition: FrontierDiscoveryNode.h:71
nav_msgs::OccupancyGrid aFrontiersMap
Definition: FrontierDiscoveryNode.h:135
std::vector< Vec2i > aFilteredCentroids
Definition: FrontierDiscoveryNode.h:144
ros::Publisher aFrontiersClustersPub
Definition: FrontierDiscoveryNode.h:126
bool aHasPose
Definition: FrontierDiscoveryNode.h:103
void ResetFrontierMsg(multirobotsimulations::Frontiers &msg)
geometry_msgs::PoseArray aPoseArrMsg
Definition: FrontierDiscoveryNode.h:132
std::string aNamespace
Definition: FrontierDiscoveryNode.h:109
std::vector< std::vector< Vec2i > > aFilteredClusters
Definition: FrontierDiscoveryNode.h:146
int aId
Definition: FrontierDiscoveryNode.h:99
nav_msgs::OccupancyGrid aOcc
Definition: FrontierDiscoveryNode.h:134
void CSpaceCallback(nav_msgs::OccupancyGrid::ConstPtr msg)
double aYaw
Definition: FrontierDiscoveryNode.h:105
std::vector< std::vector< Vec2i > > aClusters
Definition: FrontierDiscoveryNode.h:145
std::vector< ros::Subscriber > aSubscribers
Definition: FrontierDiscoveryNode.h:119