Multi-robot Playground
Alysson2024Node.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 system
45  */
46 #include <vector>
47 #include <random>
48 #include "ros/ros.h"
49 
50 /*
51  * Messages
52  */
53 #include "nav_msgs/OccupancyGrid.h"
54 #include "std_msgs/String.h"
55 #include "std_msgs/Int8MultiArray.h"
56 #include "multirobotsimulations/CustomPose.h"
57 #include "multirobotsimulations/Frontiers.h"
58 #include "multirobotsimulations/rendezvous.h"
59 #include "visualization_msgs/Marker.h"
60 
61 /*
62  * Helpers
63  */
64 #include "RendezvousPlan.h"
65 #include "Common.h"
66 
68 typedef enum {
71  state_idle = 11,
80  /*
81  * Extended state space
82  */
91 
100  public:
104  Alysson2024Node();
105 
110 
111  private:
116  void EstimatePoseCallback(multirobotsimulations::CustomPose::ConstPtr msg);
117 
122  void ClustersCallback(multirobotsimulations::Frontiers::ConstPtr msg);
123 
128  void SubGoalFinishCallback(std_msgs::String::ConstPtr msg);
129 
134  void CSpaceCallback(nav_msgs::OccupancyGrid::ConstPtr msg);
135 
140  void SetExploringCallback(std_msgs::String::ConstPtr msg);
141 
146  void SetBasestationCallback(std_msgs::String::ConstPtr msg);
147 
152  void SetIdleCallback(std_msgs::String::ConstPtr msg);
153 
158  void ChangeState(const ExplorerState& newState);
159 
168  int SelectFrontier(multirobotsimulations::Frontiers& centroids, tf::Vector3& selectFrontierWorld);
169 
177  void CreateMarker(visualization_msgs::Marker& input, const char* ns, const int& id, const int& seq);
178 
183  void SetGoal(const tf::Vector3& goal);
184 
188  void Update();
189 
190  /*
191  * Control variables
192  */
194  int aRate;
195  int aRobots;
196  int aId;
197  bool aHasPose;
198  bool aHasOcc;
199  bool aDirty;
200  bool aFirst;
201  double aDeltaTime;
203  ros::Time aLastTime;
204  tf::Vector3 aWorldPos;
205  tf::Vector3 aGoalFrontier;
206  tf::Vector3 aGoalBasestation;
207  std::string aNamespace;
210  /*
211  * Routines
212  */
213  std::vector<ros::Timer> aTimers;
215  /*
216  * Subscribers
217  */
218  std::vector<ros::Subscriber> aSubscribers;
220  /*
221  * Advertisers
222  */
223  ros::Publisher aGoalPublisher;
224  ros::Publisher aFrontierComputePublisher;
226  /*
227  * Messages
228  */
229  multirobotsimulations::Frontiers aFrontierCentroidsMsg;
230  nav_msgs::OccupancyGrid aCSpaceMsg;
232  /*
233  * Extension from Randomized-Social-Welfare policy
234  */
235 
240  bool CheckNear();
241 
247  bool CanCommunicate(const int& id);
248 
253  bool FinishedMission();
254 
261  int RandomizedFrontierSelection(multirobotsimulations::Frontiers& centroids, tf::Vector3& selectFrontierWorld);
262 
269  int SelectSubteamNewRendezvous(multirobotsimulations::Frontiers& centroids, tf::Vector3& selectFrontierWorld);
270 
275  void CommCallback(std_msgs::Int8MultiArray::ConstPtr msg);
276 
277  // extension control
278  bool aHasComm;
282  double aTimeWaiting;
283  std::shared_ptr<RendezvousPlan> aPlan;
285  // extension messages
286  std_msgs::Int8MultiArray aCommMsg;
287  multirobotsimulations::rendezvous aRendezvousMsg;
288  multirobotsimulations::CustomPose aRendezvousNewPoseMsg;
290  // extension helpers
291  tf::Vector3 aRendezvousFootprint;
292  tf::Vector3 aFirstRendezvous;
293  tf::Vector3 aGoalRendezvous;
295  std::unique_ptr<std::mt19937> aRandomNumberGenerator;
296  std::random_device aRandomNumberDevice;
298  // extension advertisers
299  ros::Publisher aPlanRealizationPublisher;
300  ros::Publisher aPlanLocationPublisher;
301 };
Alysson2024Node::SetGoal
void SetGoal(const tf::Vector3 &goal)
Set the goal location to visit, it could be a rendezvousl location or a frontier cluster center of ma...
Alysson2024Node::aCSpaceMsg
nav_msgs::OccupancyGrid aCSpaceMsg
Message used to store meta data from the occupancy grid to help converting world positions to positio...
Definition: Alysson2024Node.h:230
Alysson2024Node::aLastTime
ros::Time aLastTime
The last capatured system time used to compute the dalta time.
Definition: Alysson2024Node.h:203
Alysson2024Node::SetBasestationCallback
void SetBasestationCallback(std_msgs::String::ConstPtr msg)
Callback this node uses to go back to the basestation.
state_waiting_centroids
@ state_waiting_centroids
in this state, the robot waits for frontier clusters.
Definition: Alysson2024Node.h:76
Alysson2024Node::aGoalFrontier
tf::Vector3 aGoalFrontier
Temp variable used to store which frontier this robot should explore next.
Definition: Alysson2024Node.h:205
state_exploring
@ state_exploring
state responsible to explore a selected location.
Definition: Alysson2024Node.h:70
Alysson2024Node::aTimeWaiting
double aTimeWaiting
Counter to help checking if this robot is waiting for too long.
Definition: Alysson2024Node.h:282
Alysson2024Node::SelectFrontier
int SelectFrontier(multirobotsimulations::Frontiers &centroids, tf::Vector3 &selectFrontierWorld)
Select which frontier to explore from the message received by the FrontierDiscovery node.
Alysson2024Node::aNamespace
std::string aNamespace
The namespace of this robot.
Definition: Alysson2024Node.h:207
Alysson2024Node::aNewRendezvousLocation
tf::Vector3 aNewRendezvousLocation
Helper variable used to keep track where this robot should meet next with its current sub-team.
Definition: Alysson2024Node.h:294
state_planning
@ state_planning
in this state, the robot asks for new frontier clusters and also selects which one to explore.
Definition: Alysson2024Node.h:78
state_updating_plan
@ state_updating_plan
in this state, the consensus robot updates the plan and send to the other robots.
Definition: Alysson2024Node.h:86
Alysson2024Node::SelectSubteamNewRendezvous
int SelectSubteamNewRendezvous(multirobotsimulations::Frontiers &centroids, tf::Vector3 &selectFrontierWorld)
Select a new rendezvous location that is the frontier with the highest cost (i.e.,...
Alysson2024Node::aWaitingThreshold
double aWaitingThreshold
The maximum allowed waiting time in rendezvous location.
Definition: Alysson2024Node.h:280
Alysson2024Node::aSubscribers
std::vector< ros::Subscriber > aSubscribers
All subscribers of this node.
Definition: Alysson2024Node.h:218
state_set_rendezvous_location
@ state_set_rendezvous_location
in this state, the robot starts navigating towards its current sub-team rendezvous location.
Definition: Alysson2024Node.h:83
state_set_back_to_base
@ state_set_back_to_base
in this state, the robot navigates towards the basestation.
Definition: Alysson2024Node.h:77
Vec2i
Definition: Common.h:59
Alysson2024Node::aDirty
bool aDirty
Used to initialize the basestation location in the main loop only once.
Definition: Alysson2024Node.h:199
Alysson2024Node::aRobots
int aRobots
Number of robots this robot should be aware.
Definition: Alysson2024Node.h:195
Alysson2024Node::aGoalRendezvous
tf::Vector3 aGoalRendezvous
Helper variable that holds the location of the rendezvous location.
Definition: Alysson2024Node.h:293
Alysson2024Node::aFrontierCentroidsMsg
multirobotsimulations::Frontiers aFrontierCentroidsMsg
Message used to receive frontier clusters.
Definition: Alysson2024Node.h:229
Alysson2024Node::aDeltaTime
double aDeltaTime
Delta time between iterations in the main loop.
Definition: Alysson2024Node.h:201
state_navigating_to_rendezvous
@ state_navigating_to_rendezvous
in this state, the robot simply navigate towards the assigned rendezvous location.
Definition: Alysson2024Node.h:84
Alysson2024Node
Node that implements the intermittent communication policy.
Definition: Alysson2024Node.h:99
Alysson2024Node::aRandomNumberGenerator
std::unique_ptr< std::mt19937 > aRandomNumberGenerator
Random number generator for randomized social welfare.
Definition: Alysson2024Node.h:295
Alysson2024Node::aGoalBasestation
tf::Vector3 aGoalBasestation
The goal position of the basestation.
Definition: Alysson2024Node.h:206
Alysson2024Node::aPlan
std::shared_ptr< RendezvousPlan > aPlan
The rendezvous plan object used to control how agreements are executed, their order,...
Definition: Alysson2024Node.h:283
Alysson2024Node::CheckNear
bool CheckNear()
Used to help checking if there are other robots nearby.
Alysson2024Node::aRendezvousFootprint
tf::Vector3 aRendezvousFootprint
The rendezvous location this robot should go when inside a rendezous zone.
Definition: Alysson2024Node.h:291
state_select_new_rendezvous
@ state_select_new_rendezvous
in this state, the consensus robot sends the new rendezvous locations to all other robots.
Definition: Alysson2024Node.h:89
state_select_frontier
@ state_select_frontier
state responsible to select which frontier cluster to explore.
Definition: Alysson2024Node.h:69
Alysson2024Node::SetExploringCallback
void SetExploringCallback(std_msgs::String::ConstPtr msg)
Callback this node uses to change its internal state to start exploring.
Alysson2024Node::EstimatePoseCallback
void EstimatePoseCallback(multirobotsimulations::CustomPose::ConstPtr msg)
Callback for pose estimator from the SLAM algorithm.
state_waiting_consensus
@ state_waiting_consensus
in this state, the other robots wait for the information from the consensus robot.
Definition: Alysson2024Node.h:87
Alysson2024Node::aRendezvousNewPoseMsg
multirobotsimulations::CustomPose aRendezvousNewPoseMsg
Custom pose used to tell the other robots which location they should meet next with their current sub...
Definition: Alysson2024Node.h:288
Alysson2024Node::ClustersCallback
void ClustersCallback(multirobotsimulations::Frontiers::ConstPtr msg)
Callback for the FrontierDiscovery node to update rendezvous locations or for planning.
Alysson2024Node::aRate
int aRate
Main loop rate.
Definition: Alysson2024Node.h:194
Alysson2024Node::aHasOcc
bool aHasOcc
Used to known when this robot received its OccupancyGrid information from the SLAM sub-system.
Definition: Alysson2024Node.h:198
Alysson2024Node::aTimers
std::vector< ros::Timer > aTimers
Routines of this node.
Definition: Alysson2024Node.h:213
Alysson2024Node::aPlanRealizationPublisher
ros::Publisher aPlanRealizationPublisher
Publisher used to help synchronize who is fulfilling a rendezvous agreement.
Definition: Alysson2024Node.h:299
Alysson2024Node::CSpaceCallback
void CSpaceCallback(nav_msgs::OccupancyGrid::ConstPtr msg)
Callback from the MapStitching node that is used to receive meta data from the map.
state_exploration_finished
@ state_exploration_finished
this states marks the end of the mission when all frontiers were explored.
Definition: Alysson2024Node.h:72
Alysson2024Node::Alysson2024Node
Alysson2024Node()
Default constructor that initializes all ros advertisers, publishers, and routines.
Alysson2024Node::aId
int aId
Unique id.
Definition: Alysson2024Node.h:196
Alysson2024Node::aGoalPublisher
ros::Publisher aGoalPublisher
This publisher is used to tell the global planner, which goal location the robot should visit next.
Definition: Alysson2024Node.h:223
Alysson2024Node::CommCallback
void CommCallback(std_msgs::Int8MultiArray::ConstPtr msg)
Callback of the MockCommunication model used to check which robots are nearby.
Alysson2024Node::aRandomNumberDevice
std::random_device aRandomNumberDevice
Random device to use with std::mt19937 to generate random numbers.
Definition: Alysson2024Node.h:296
state_idle
@ state_idle
in this state the robot waits for commands.
Definition: Alysson2024Node.h:71
Alysson2024Node::~Alysson2024Node
~Alysson2024Node()
Default destructor.
Alysson2024Node::aReceivedNewRendezvousLocation
bool aReceivedNewRendezvousLocation
Flag used to check if this robot received new rendezvous location in the it is not the consensus robo...
Definition: Alysson2024Node.h:279
ExplorerState
ExplorerState
Definition: Alysson2024Node.h:68
Alysson2024Node::aCurrentState
ExplorerState aCurrentState
The current state of the robot.
Definition: Alysson2024Node.h:208
Alysson2024Node::ChangeState
void ChangeState(const ExplorerState &newState)
Change the state of the robot and print information about the change.
Alysson2024Node::aFrontierComputePublisher
ros::Publisher aFrontierComputePublisher
This publisher is used to request the FrontierDiscovery module to compute new frontier clusters.
Definition: Alysson2024Node.h:224
state_back_to_base
@ state_back_to_base
this state tells that the robot is going to the initial basestation location.
Definition: Alysson2024Node.h:73
Common.h
RendezvousPlan.h
Alysson2024Node::Update
void Update()
Node's main update routine.
Alysson2024Node::aHasComm
bool aHasComm
Flag used to check if the robot received the mock communication model communications array.
Definition: Alysson2024Node.h:278
Alysson2024Node::aFirstRendezvous
tf::Vector3 aFirstRendezvous
Store the location of the first rendezvous location for all sub-teams.
Definition: Alysson2024Node.h:292
Alysson2024Node::aFirst
bool aFirst
Used to skip the first delta time calculation to avoid major errors.
Definition: Alysson2024Node.h:200
Alysson2024Node::aCommMsg
std_msgs::Int8MultiArray aCommMsg
Message to receive information from the mock communication model node.
Definition: Alysson2024Node.h:286
Alysson2024Node::CreateMarker
void CreateMarker(visualization_msgs::Marker &input, const char *ns, const int &id, const int &seq)
Create a marker to mark selected goal locations (e.g., rendezvous locations or frontier clusters).
Alysson2024Node::aWorldPos
tf::Vector3 aWorldPos
The position of the robot in the world reference frame.
Definition: Alysson2024Node.h:204
state_compute_centroids
@ state_compute_centroids
used to wait for the FrontierDiscovery to return frontier clusters.
Definition: Alysson2024Node.h:75
Alysson2024Node::FinishedMission
bool FinishedMission()
Check if there are places left to explore.
Alysson2024Node::SetIdleCallback
void SetIdleCallback(std_msgs::String::ConstPtr msg)
Callback this node uses to stop the mission and enter in idle mode.
state_back_to_base_finished
@ state_back_to_base_finished
this state is used to identify when the robot reached the basestation.
Definition: Alysson2024Node.h:74
Alysson2024Node::SubGoalFinishCallback
void SubGoalFinishCallback(std_msgs::String::ConstPtr msg)
Callback from the IntegratedGlobalPlanner node that is called when the robot reached the assigned goa...
Alysson2024Node::aHasPose
bool aHasPose
Used to known when this robot received its estimate pose from the SLAM sub-system.
Definition: Alysson2024Node.h:197
Alysson2024Node::aPlanLocationPublisher
ros::Publisher aPlanLocationPublisher
Publisher to broadcast new rendezvous locations for the current sub-team.
Definition: Alysson2024Node.h:300
state_waiting_centroids_for_plan
@ state_waiting_centroids_for_plan
in this state the consensus robot waits for clusters to use as reference updates for new rendezvous l...
Definition: Alysson2024Node.h:88
Alysson2024Node::aQueueSize
int aQueueSize
Size of all publishers and subscribers queues.
Definition: Alysson2024Node.h:193
state_at_rendezvous
@ state_at_rendezvous
in this state, the robot reached the rendezvous location and can start updating the plan or waiting f...
Definition: Alysson2024Node.h:85
Alysson2024Node::aRendezvousMsg
multirobotsimulations::rendezvous aRendezvousMsg
Message that helps the consensus robot sending new rendezvous locations to other robots.
Definition: Alysson2024Node.h:287
Alysson2024Node::aOccPos
Vec2i aOccPos
The position of the robot in the Occupancy Grid reference frame.
Definition: Alysson2024Node.h:202
Alysson2024Node::CanCommunicate
bool CanCommunicate(const int &id)
Used to check if this robot can communicate with another.
Alysson2024Node::RandomizedFrontierSelection
int RandomizedFrontierSelection(multirobotsimulations::Frontiers &centroids, tf::Vector3 &selectFrontierWorld)
Select a randomized frontier.