Multi-robot Playground
LocalCSpaceNode.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  * LocalCSpaceNode class
70  */
72  public:
75 
76  private:
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,
82  tf::Vector3& occPose,
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);
91 
92  void ApplyDynamicData(nav_msgs::OccupancyGrid& occ,
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);
98  void ClearLocalTrajectories(std::vector<geometry_msgs::PoseArray>& local,
99  std_msgs::Int8MultiArray& comm);
100 
101  void RobotsInCommCallback(std_msgs::Int8MultiArray::ConstPtr msg);
102  void OccCallback(nav_msgs::OccupancyGrid::ConstPtr msg);
103  void WorldPoseCallback(multirobotsimulations::CustomPose::ConstPtr msg);
104 
105  void Update();
106 
107 
108  /*
109  * Control variables
110  */
112  int aId;
114  int aRobots;
116  bool aHasOcc;
117  bool aHasPose;
119  double aRate;
120  double aLidarRange;
123  tf::Vector3 aOccPose;
124  std::string aNamespace;
125 
126 
127  /*
128  * Routines
129  */
130  std::vector<ros::Timer> aTimers;
131 
132  /*
133  * Subscribers
134  */
135  std::vector<ros::Subscriber> aSubscribers;
136 
137  /*
138  * Advertisers
139  */
140  ros::Publisher aObstaclesPublisher;
141  ros::Publisher aLocalCSpacePublisher;
143  ros::Publisher aFreePositionsPublisher;
144 
145  /*
146  * Messages
147  */
148  nav_msgs::OccupancyGrid aOccMsg;
149  nav_msgs::OccupancyGrid aOccWithDynamicDataMsg;
150  nav_msgs::OccupancyGrid aLocalCspaceMsg;
151  std_msgs::Int8MultiArray aRobotsInCommMsg;
152  multirobotsimulations::CustomPose aWorldPoseMsg;
153  geometry_msgs::PoseArray aOccupiedPosesMsg;
154  geometry_msgs::PoseArray aFreePosesMsg;
155 
156  /*
157  * Helpers
158  */
159  std::vector<geometry_msgs::PoseArray> aTrajectoriesArray;
160  std::vector<geometry_msgs::PoseArray> aLidarsArray;
161 };
LocalCSpaceNode::aLocalCspaceMsg
nav_msgs::OccupancyGrid aLocalCspaceMsg
Definition: LocalCSpaceNode.h:150
LocalCSpaceNode::aTimers
std::vector< ros::Timer > aTimers
Definition: LocalCSpaceNode.h:130
LocalCSpaceNode::aFreePosesMsg
geometry_msgs::PoseArray aFreePosesMsg
Definition: LocalCSpaceNode.h:154
LocalCSpaceNode::aOccWithDynamicDataMsg
nav_msgs::OccupancyGrid aOccWithDynamicDataMsg
Definition: LocalCSpaceNode.h:149
LocalCSpaceNode::aOccMsg
nav_msgs::OccupancyGrid aOccMsg
Definition: LocalCSpaceNode.h:148
LocalCSpaceNode::aRate
double aRate
Definition: LocalCSpaceNode.h:119
LocalCSpaceNode::aObstaclesPublisher
ros::Publisher aObstaclesPublisher
Definition: LocalCSpaceNode.h:140
LocalCSpaceNode::aLidarSources
int aLidarSources
Definition: LocalCSpaceNode.h:113
LocalCSpaceNode::aLocalCSpacePublisher
ros::Publisher aLocalCSpacePublisher
Definition: LocalCSpaceNode.h:141
LocalCSpaceNode::aTrajectoriesArray
std::vector< geometry_msgs::PoseArray > aTrajectoriesArray
Definition: LocalCSpaceNode.h:159
LocalCSpaceNode::aId
int aId
Definition: LocalCSpaceNode.h:112
LocalCSpaceNode::aWorldPoseMsg
multirobotsimulations::CustomPose aWorldPoseMsg
Definition: LocalCSpaceNode.h:152
LocalCSpaceNode::Update
void Update()
LocalCSpaceNode::aLidarsArray
std::vector< geometry_msgs::PoseArray > aLidarsArray
Definition: LocalCSpaceNode.h:160
LocalCSpaceNode::ApplyDynamicData
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)
LocalCSpaceNode::RobotsInCommCallback
void RobotsInCommCallback(std_msgs::Int8MultiArray::ConstPtr msg)
LocalCSpaceNode::aQueueSize
int aQueueSize
Definition: LocalCSpaceNode.h:111
LocalCSpaceNode::aOccuInflateRadius
double aOccuInflateRadius
Definition: LocalCSpaceNode.h:122
LocalCSpaceNode::aSubscribers
std::vector< ros::Subscriber > aSubscribers
Definition: LocalCSpaceNode.h:135
LocalCSpaceNode::LocalCSpaceNode
LocalCSpaceNode()
LocalCSpaceNode::aHasPose
bool aHasPose
Definition: LocalCSpaceNode.h:117
LocalCSpaceNode
Definition: LocalCSpaceNode.h:71
LocalCSpaceNode::aRobots
int aRobots
Definition: LocalCSpaceNode.h:114
LocalCSpaceNode::~LocalCSpaceNode
~LocalCSpaceNode()
LocalCSpaceNode::aOccupiedPositionsPublisher
ros::Publisher aOccupiedPositionsPublisher
Definition: LocalCSpaceNode.h:142
LocalCSpaceNode::aHasOcc
bool aHasOcc
Definition: LocalCSpaceNode.h:116
LocalCSpaceNode::ClearLocalTrajectories
void ClearLocalTrajectories(std::vector< geometry_msgs::PoseArray > &local, std_msgs::Int8MultiArray &comm)
LocalCSpaceNode::CreateLocal
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)
LocalCSpaceNode::aFreePositionsPublisher
ros::Publisher aFreePositionsPublisher
Definition: LocalCSpaceNode.h:143
LocalCSpaceNode::aFreeInflateRadius
double aFreeInflateRadius
Definition: LocalCSpaceNode.h:121
LocalCSpaceNode::aLocalViewSize
int aLocalViewSize
Definition: LocalCSpaceNode.h:115
Common.h
LocalCSpaceNode::aReceivedComm
bool aReceivedComm
Definition: LocalCSpaceNode.h:118
LocalCSpaceNode::WorldPoseCallback
void WorldPoseCallback(multirobotsimulations::CustomPose::ConstPtr msg)
LocalCSpaceNode::aOccPose
tf::Vector3 aOccPose
Definition: LocalCSpaceNode.h:123
LocalCSpaceNode::aOccupiedPosesMsg
geometry_msgs::PoseArray aOccupiedPosesMsg
Definition: LocalCSpaceNode.h:153
LocalCSpaceNode::aNamespace
std::string aNamespace
Definition: LocalCSpaceNode.h:124
LocalCSpaceNode::aRobotsInCommMsg
std_msgs::Int8MultiArray aRobotsInCommMsg
Definition: LocalCSpaceNode.h:151
LocalCSpaceNode::aLidarRange
double aLidarRange
Definition: LocalCSpaceNode.h:120
LocalCSpaceNode::OccCallback
void OccCallback(nav_msgs::OccupancyGrid::ConstPtr msg)