 |
Multi-robot Playground
|
Go to the documentation of this file.
51 #include "ros/package.h"
56 #include "geometry_msgs/Pose.h"
57 #include "nav_msgs/OccupancyGrid.h"
58 #include "geometry_msgs/PoseArray.h"
59 #include "multirobotsimulations/CustomPose.h"
60 #include "multirobotsimulations/MockPackage.h"
61 #include "std_msgs/Float64MultiArray.h"
62 #include "std_msgs/Int8MultiArray.h"
63 #include "visualization_msgs/Marker.h"
64 #include "visualization_msgs/MarkerArray.h"
79 void OccCallback(nav_msgs::OccupancyGrid::ConstPtr msg);
80 void Fusemaps(nav_msgs::OccupancyGrid& occ,
81 nav_msgs::OccupancyGrid& other,
82 geometry_msgs::Pose& relative,
std::vector< ros::Timer > aTimers
Definition: MapStitchingNode.h:99
bool aDirty
Definition: MapStitchingNode.h:92
nav_msgs::OccupancyGrid aFusionMsg
Definition: MapStitchingNode.h:114
std::vector< nav_msgs::OccupancyGrid > aRobotsOcc
Definition: MapStitchingNode.h:121
std::vector< ros::Subscriber > aSubscribers
Definition: MapStitchingNode.h:104
std::string aNamespace
Definition: MapStitchingNode.h:94
double aRate
Definition: MapStitchingNode.h:93
std::vector< bool > aReceivedOccs
Definition: MapStitchingNode.h:122
int aQueueSize
Definition: MapStitchingNode.h:89
std_msgs::Int8MultiArray aRobotsInCommMsg
Definition: MapStitchingNode.h:115
ros::Publisher aFusionPublisher
Definition: MapStitchingNode.h:109
int aId
Definition: MapStitchingNode.h:90
Definition: MapStitchingNode.h:71
geometry_msgs::PoseArray aRobotsRelativePosesMsg
Definition: MapStitchingNode.h:116
void CommunicationsCallback(std_msgs::Int8MultiArray::ConstPtr msg)
void OccCallback(nav_msgs::OccupancyGrid::ConstPtr msg)
void RelativeStartingPosesCallback(geometry_msgs::PoseArray::ConstPtr msg)
int aRobots
Definition: MapStitchingNode.h:91
bool aReceivedRelativePoses
Definition: MapStitchingNode.h:123
void Fusemaps(nav_msgs::OccupancyGrid &occ, nav_msgs::OccupancyGrid &other, geometry_msgs::Pose &relative, const bool &replace)