 |
Multi-robot Playground
|
Go to the documentation of this file.
55 #include "multirobotsimulations/CustomOcc.h"
56 #include "nav_msgs/OccupancyGrid.h"
57 #include "geometry_msgs/PoseArray.h"
58 #include "geometry_msgs/Pose.h"
59 #include "costmap_converter/ObstacleArrayMsg.h"
60 #include "std_msgs/Int8MultiArray.h"
61 #include "multirobotsimulations/CustomPose.h"
77 void CreateLocal(nav_msgs::OccupancyGrid& dynamicOcc,
78 nav_msgs::OccupancyGrid& localMap,
79 geometry_msgs::PoseArray& occupiedPoses,
80 geometry_msgs::PoseArray& freePoses,
81 tf::Vector3& worldPose,
83 const double& freeInflationRadius,
84 const double& occupiedInflationRadius,
85 const int& windws_size_meters,
86 const int8_t& occupancyThreshold = 90,
87 const int8_t& freeThreshold = 50,
88 const int8_t& occupiedValue = 100,
89 const int8_t& freeVal = 1,
90 const int8_t& unknownVal = -1);
93 nav_msgs::OccupancyGrid& dynamicOcc,
94 std::vector<geometry_msgs::PoseArray>& lidarSources,
95 std::vector<geometry_msgs::PoseArray>& otherSources,
96 const double& maxLidarRange = 10.0,
97 const int8_t& occupiedValue = 100);
99 std_msgs::Int8MultiArray& comm);
102 void OccCallback(nav_msgs::OccupancyGrid::ConstPtr msg);
nav_msgs::OccupancyGrid aLocalCspaceMsg
Definition: LocalCSpaceNode.h:150
std::vector< ros::Timer > aTimers
Definition: LocalCSpaceNode.h:130
geometry_msgs::PoseArray aFreePosesMsg
Definition: LocalCSpaceNode.h:154
nav_msgs::OccupancyGrid aOccWithDynamicDataMsg
Definition: LocalCSpaceNode.h:149
nav_msgs::OccupancyGrid aOccMsg
Definition: LocalCSpaceNode.h:148
double aRate
Definition: LocalCSpaceNode.h:119
ros::Publisher aObstaclesPublisher
Definition: LocalCSpaceNode.h:140
int aLidarSources
Definition: LocalCSpaceNode.h:113
ros::Publisher aLocalCSpacePublisher
Definition: LocalCSpaceNode.h:141
std::vector< geometry_msgs::PoseArray > aTrajectoriesArray
Definition: LocalCSpaceNode.h:159
int aId
Definition: LocalCSpaceNode.h:112
multirobotsimulations::CustomPose aWorldPoseMsg
Definition: LocalCSpaceNode.h:152
std::vector< geometry_msgs::PoseArray > aLidarsArray
Definition: LocalCSpaceNode.h:160
void ApplyDynamicData(nav_msgs::OccupancyGrid &occ, nav_msgs::OccupancyGrid &dynamicOcc, std::vector< geometry_msgs::PoseArray > &lidarSources, std::vector< geometry_msgs::PoseArray > &otherSources, const double &maxLidarRange=10.0, const int8_t &occupiedValue=100)
void RobotsInCommCallback(std_msgs::Int8MultiArray::ConstPtr msg)
int aQueueSize
Definition: LocalCSpaceNode.h:111
double aOccuInflateRadius
Definition: LocalCSpaceNode.h:122
std::vector< ros::Subscriber > aSubscribers
Definition: LocalCSpaceNode.h:135
bool aHasPose
Definition: LocalCSpaceNode.h:117
Definition: LocalCSpaceNode.h:71
int aRobots
Definition: LocalCSpaceNode.h:114
ros::Publisher aOccupiedPositionsPublisher
Definition: LocalCSpaceNode.h:142
bool aHasOcc
Definition: LocalCSpaceNode.h:116
void ClearLocalTrajectories(std::vector< geometry_msgs::PoseArray > &local, std_msgs::Int8MultiArray &comm)
void CreateLocal(nav_msgs::OccupancyGrid &dynamicOcc, nav_msgs::OccupancyGrid &localMap, geometry_msgs::PoseArray &occupiedPoses, geometry_msgs::PoseArray &freePoses, tf::Vector3 &worldPose, tf::Vector3 &occPose, const double &freeInflationRadius, const double &occupiedInflationRadius, const int &windws_size_meters, const int8_t &occupancyThreshold=90, const int8_t &freeThreshold=50, const int8_t &occupiedValue=100, const int8_t &freeVal=1, const int8_t &unknownVal=-1)
ros::Publisher aFreePositionsPublisher
Definition: LocalCSpaceNode.h:143
double aFreeInflateRadius
Definition: LocalCSpaceNode.h:121
int aLocalViewSize
Definition: LocalCSpaceNode.h:115
bool aReceivedComm
Definition: LocalCSpaceNode.h:118
void WorldPoseCallback(multirobotsimulations::CustomPose::ConstPtr msg)
tf::Vector3 aOccPose
Definition: LocalCSpaceNode.h:123
geometry_msgs::PoseArray aOccupiedPosesMsg
Definition: LocalCSpaceNode.h:153
std::string aNamespace
Definition: LocalCSpaceNode.h:124
std_msgs::Int8MultiArray aRobotsInCommMsg
Definition: LocalCSpaceNode.h:151
double aLidarRange
Definition: LocalCSpaceNode.h:120
void OccCallback(nav_msgs::OccupancyGrid::ConstPtr msg)