Multi-robot Playground
CSpaceNode.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020, Alysson Ribeiro da Silva
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * 3. All advertising materials mentioning features or use of this software must
16  * display the following acknowledgement:
17  * This product includes software developed by Alysson Ribeiro da Silva.
18  *
19  * 4. Neither the name of the copyright holder nor the names of its
20  * contributors may be used to endorse or promote products derived from
21  * this software without specific prior written permission.
22  *
23  * 5. The source and the binary form, and any modifications made to them
24  * may not be used for the purpose of training or improving machine learning
25  * algorithms, including but not limited to artificial intelligence, natural
26  * language processing, or data mining. This condition applies to any derivatives,
27  * modifications, or updates based on the Software code. Any usage of the source
28  * or the binary form in an AI-training dataset is considered a breach of
29  * this License.
30  *
31  * THIS SOFTWARE IS PROVIDED BY COPYRIGHT HOLDER "AS IS" AND ANY EXPRESS OR
32  * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
33  * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO
34  * EVENT SHALL COPYRIGHT HOLDER BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
35  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
36  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
37  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
38  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
39  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
40  * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
41 */
42 
43 /*
44  * Ros and systems
45  */
46 #include <string>
47 #include <ros/ros.h>
48 #include <signal.h>
49 #include "tf/tf.h"
50 #include "string.h"
51 
52 /*
53  * Messages
54  */
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"
62 
63 /*
64  * Helpers
65  */
66 #include "Common.h"
67 
68 /*
69  * CSpaceNode class
70  */
71 class CSpaceNode {
72  public:
73  CSpaceNode();
74  ~CSpaceNode();
75 
76  private:
77  void Inflate(nav_msgs::OccupancyGrid& occ,
78  nav_msgs::OccupancyGrid& free,
79  nav_msgs::OccupancyGrid& occupied,
80  const double& freeInflationRadius,
81  const double& occupiedInflationRadius,
82  const int8_t& occupancyThreshold = 90,
83  const int8_t& freeThreshold = 50,
84  const int8_t& occupiedValue = 100,
85  const int8_t& freeVal = 1);
86 
87  void ApplyDynamicData(nav_msgs::OccupancyGrid& occ,
88  nav_msgs::OccupancyGrid& dynamicOcc,
89  std::vector<geometry_msgs::PoseArray>& lidarSources,
90  const double& maxLidarRange = 10.0,
91  const int8_t& occupiedValue = 100);
92 
93  void ApplyDynamicData(nav_msgs::OccupancyGrid& occ,
94  nav_msgs::OccupancyGrid& dynamicOcc,
95  std::vector<geometry_msgs::PoseArray>& lidarSources,
96  std::vector<geometry_msgs::PoseArray>& otherSources,
97  const double& maxLidarRange = 10.0,
98  const int8_t& occupiedValue = 100);
99 
100  void GenerateCSpace(nav_msgs::OccupancyGrid& free,
101  nav_msgs::OccupancyGrid& occupied,
102  nav_msgs::OccupancyGrid& cspace,
103  tf::Vector3& occ_pose,
104  const int8_t& unknownVal = -1);
105 
106  void InflatePoseForPlanner(nav_msgs::OccupancyGrid& cspace,
107  const double& freeInflationRadius,
108  const int& x,
109  const int& y,
110  const int8_t& occupancyThreshold = 90,
111  const int8_t& freeVal = 1);
112 
113  void ClearLocalTrajectories(std::vector<geometry_msgs::PoseArray>& local,
114  std_msgs::Int8MultiArray& comm);
115 
116  void RobotsInCommCallback(std_msgs::Int8MultiArray::ConstPtr msg);
117  void OccCallback(nav_msgs::OccupancyGrid::ConstPtr msg);
118  void WorldPoseCallback(multirobotsimulations::CustomPose::ConstPtr msg);
119 
120  void Update();
121 
122 
123  /*
124  * Control variables
125  */
127  int aId;
129  int aRobots;
130  bool aHasOcc;
131  bool aHasPose;
133  double aRate;
134  double aLidarRange;
137  tf::Vector3 aOccPose;
138  std::string aNamespace;
139 
140  /*
141  * Routines
142  */
143  std::vector<ros::Timer> aTimers;
144 
145  /*
146  * Subscribers
147  */
148  std::vector<ros::Subscriber> aSubscribers;
149 
150  /*
151  * Advertisers
152  */
153  ros::Publisher aCspacePublisher;
154 
155  /*
156  * Messages
157  */
158  nav_msgs::OccupancyGrid aOccMsg;
159  nav_msgs::OccupancyGrid aFreeCellsMsg;
160  nav_msgs::OccupancyGrid aOccupiedCellsMsg;
161  nav_msgs::OccupancyGrid aOccWithDynamicDataMsg;
162  nav_msgs::OccupancyGrid aCspaceMsg;
163  multirobotsimulations::CustomPose aWorldPoseMsg;
164  std_msgs::Int8MultiArray aRobotsInCommMsg;
165 
166  /*
167  * Helpers
168  */
169  std::vector<geometry_msgs::PoseArray> aTrajectoriesArray;
170  std::vector<geometry_msgs::PoseArray> aLidarsArray;
171 };
CSpaceNode::aTrajectoriesArray
std::vector< geometry_msgs::PoseArray > aTrajectoriesArray
Definition: CSpaceNode.h:169
CSpaceNode::aLidarSources
int aLidarSources
Definition: CSpaceNode.h:128
CSpaceNode::aWorldPoseMsg
multirobotsimulations::CustomPose aWorldPoseMsg
Definition: CSpaceNode.h:163
CSpaceNode::WorldPoseCallback
void WorldPoseCallback(multirobotsimulations::CustomPose::ConstPtr msg)
CSpaceNode::aHasOcc
bool aHasOcc
Definition: CSpaceNode.h:130
CSpaceNode::GenerateCSpace
void GenerateCSpace(nav_msgs::OccupancyGrid &free, nav_msgs::OccupancyGrid &occupied, nav_msgs::OccupancyGrid &cspace, tf::Vector3 &occ_pose, const int8_t &unknownVal=-1)
CSpaceNode::CSpaceNode
CSpaceNode()
CSpaceNode::aCspacePublisher
ros::Publisher aCspacePublisher
Definition: CSpaceNode.h:153
CSpaceNode::aSubscribers
std::vector< ros::Subscriber > aSubscribers
Definition: CSpaceNode.h:148
CSpaceNode::aReceivedComm
bool aReceivedComm
Definition: CSpaceNode.h:132
CSpaceNode
Definition: CSpaceNode.h:71
CSpaceNode::aRobotsInCommMsg
std_msgs::Int8MultiArray aRobotsInCommMsg
Definition: CSpaceNode.h:164
CSpaceNode::Update
void Update()
CSpaceNode::OccCallback
void OccCallback(nav_msgs::OccupancyGrid::ConstPtr msg)
CSpaceNode::ApplyDynamicData
void ApplyDynamicData(nav_msgs::OccupancyGrid &occ, nav_msgs::OccupancyGrid &dynamicOcc, std::vector< geometry_msgs::PoseArray > &lidarSources, const double &maxLidarRange=10.0, const int8_t &occupiedValue=100)
CSpaceNode::Inflate
void Inflate(nav_msgs::OccupancyGrid &occ, nav_msgs::OccupancyGrid &free, nav_msgs::OccupancyGrid &occupied, const double &freeInflationRadius, const double &occupiedInflationRadius, const int8_t &occupancyThreshold=90, const int8_t &freeThreshold=50, const int8_t &occupiedValue=100, const int8_t &freeVal=1)
CSpaceNode::aLidarsArray
std::vector< geometry_msgs::PoseArray > aLidarsArray
Definition: CSpaceNode.h:170
CSpaceNode::aCspaceMsg
nav_msgs::OccupancyGrid aCspaceMsg
Definition: CSpaceNode.h:162
CSpaceNode::aHasPose
bool aHasPose
Definition: CSpaceNode.h:131
CSpaceNode::aOccuInflateRadius
double aOccuInflateRadius
Definition: CSpaceNode.h:136
CSpaceNode::aRobots
int aRobots
Definition: CSpaceNode.h:129
CSpaceNode::aOccPose
tf::Vector3 aOccPose
Definition: CSpaceNode.h:137
CSpaceNode::~CSpaceNode
~CSpaceNode()
CSpaceNode::InflatePoseForPlanner
void InflatePoseForPlanner(nav_msgs::OccupancyGrid &cspace, const double &freeInflationRadius, const int &x, const int &y, const int8_t &occupancyThreshold=90, const int8_t &freeVal=1)
CSpaceNode::aQueueSize
int aQueueSize
Definition: CSpaceNode.h:126
CSpaceNode::aOccWithDynamicDataMsg
nav_msgs::OccupancyGrid aOccWithDynamicDataMsg
Definition: CSpaceNode.h:161
Common.h
CSpaceNode::aFreeCellsMsg
nav_msgs::OccupancyGrid aFreeCellsMsg
Definition: CSpaceNode.h:159
CSpaceNode::ClearLocalTrajectories
void ClearLocalTrajectories(std::vector< geometry_msgs::PoseArray > &local, std_msgs::Int8MultiArray &comm)
CSpaceNode::aOccMsg
nav_msgs::OccupancyGrid aOccMsg
Definition: CSpaceNode.h:158
CSpaceNode::aRate
double aRate
Definition: CSpaceNode.h:133
CSpaceNode::RobotsInCommCallback
void RobotsInCommCallback(std_msgs::Int8MultiArray::ConstPtr msg)
CSpaceNode::aTimers
std::vector< ros::Timer > aTimers
Definition: CSpaceNode.h:143
CSpaceNode::aLidarRange
double aLidarRange
Definition: CSpaceNode.h:134
CSpaceNode::aId
int aId
Definition: CSpaceNode.h:127
CSpaceNode::aNamespace
std::string aNamespace
Definition: CSpaceNode.h:138
CSpaceNode::aFreeInflateRadius
double aFreeInflateRadius
Definition: CSpaceNode.h:135
CSpaceNode::aOccupiedCellsMsg
nav_msgs::OccupancyGrid aOccupiedCellsMsg
Definition: CSpaceNode.h:160