Multi-robot Playground
Alysson2024Node Class Reference

Node that implements the intermittent communication policy. More...

#include <Alysson2024Node.h>

Collaboration diagram for Alysson2024Node:

Public Member Functions

 Alysson2024Node ()
 Default constructor that initializes all ros advertisers, publishers, and routines. More...
 
 ~Alysson2024Node ()
 Default destructor. More...
 

Private Member Functions

void EstimatePoseCallback (multirobotsimulations::CustomPose::ConstPtr msg)
 Callback for pose estimator from the SLAM algorithm. More...
 
void ClustersCallback (multirobotsimulations::Frontiers::ConstPtr msg)
 Callback for the FrontierDiscovery node to update rendezvous locations or for planning. More...
 
void SubGoalFinishCallback (std_msgs::String::ConstPtr msg)
 Callback from the IntegratedGlobalPlanner node that is called when the robot reached the assigned goal. More...
 
void CSpaceCallback (nav_msgs::OccupancyGrid::ConstPtr msg)
 Callback from the MapStitching node that is used to receive meta data from the map. More...
 
void SetExploringCallback (std_msgs::String::ConstPtr msg)
 Callback this node uses to change its internal state to start exploring. More...
 
void SetBasestationCallback (std_msgs::String::ConstPtr msg)
 Callback this node uses to go back to the basestation. More...
 
void SetIdleCallback (std_msgs::String::ConstPtr msg)
 Callback this node uses to stop the mission and enter in idle mode. More...
 
void ChangeState (const ExplorerState &newState)
 Change the state of the robot and print information about the change. More...
 
int SelectFrontier (multirobotsimulations::Frontiers &centroids, tf::Vector3 &selectFrontierWorld)
 Select which frontier to explore from the message received by the FrontierDiscovery node. More...
 
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). More...
 
void SetGoal (const tf::Vector3 &goal)
 Set the goal location to visit, it could be a rendezvousl location or a frontier cluster center of mass. More...
 
void Update ()
 Node's main update routine. More...
 
bool CheckNear ()
 Used to help checking if there are other robots nearby. More...
 
bool CanCommunicate (const int &id)
 Used to check if this robot can communicate with another. More...
 
bool FinishedMission ()
 Check if there are places left to explore. More...
 
int RandomizedFrontierSelection (multirobotsimulations::Frontiers &centroids, tf::Vector3 &selectFrontierWorld)
 Select a randomized frontier. More...
 
int SelectSubteamNewRendezvous (multirobotsimulations::Frontiers &centroids, tf::Vector3 &selectFrontierWorld)
 Select a new rendezvous location that is the frontier with the highest cost (i.e., that spread the robots the most). More...
 
void CommCallback (std_msgs::Int8MultiArray::ConstPtr msg)
 Callback of the MockCommunication model used to check which robots are nearby. More...
 

Private Attributes

int aQueueSize
 Size of all publishers and subscribers queues. More...
 
int aRate
 Main loop rate. More...
 
int aRobots
 Number of robots this robot should be aware. More...
 
int aId
 Unique id. More...
 
bool aHasPose
 Used to known when this robot received its estimate pose from the SLAM sub-system. More...
 
bool aHasOcc
 Used to known when this robot received its OccupancyGrid information from the SLAM sub-system. More...
 
bool aDirty
 Used to initialize the basestation location in the main loop only once. More...
 
bool aFirst
 Used to skip the first delta time calculation to avoid major errors. More...
 
double aDeltaTime
 Delta time between iterations in the main loop. More...
 
Vec2i aOccPos
 The position of the robot in the Occupancy Grid reference frame. More...
 
ros::Time aLastTime
 The last capatured system time used to compute the dalta time. More...
 
tf::Vector3 aWorldPos
 The position of the robot in the world reference frame. More...
 
tf::Vector3 aGoalFrontier
 Temp variable used to store which frontier this robot should explore next. More...
 
tf::Vector3 aGoalBasestation
 The goal position of the basestation. More...
 
std::string aNamespace
 The namespace of this robot. More...
 
ExplorerState aCurrentState
 The current state of the robot. More...
 
std::vector< ros::Timer > aTimers
 Routines of this node. More...
 
std::vector< ros::Subscriber > aSubscribers
 All subscribers of this node. More...
 
ros::Publisher aGoalPublisher
 This publisher is used to tell the global planner, which goal location the robot should visit next. More...
 
ros::Publisher aFrontierComputePublisher
 This publisher is used to request the FrontierDiscovery module to compute new frontier clusters. More...
 
multirobotsimulations::Frontiers aFrontierCentroidsMsg
 Message used to receive frontier clusters. More...
 
nav_msgs::OccupancyGrid aCSpaceMsg
 Message used to store meta data from the occupancy grid to help converting world positions to positions in the grid. More...
 
bool aHasComm
 Flag used to check if the robot received the mock communication model communications array. More...
 
bool aReceivedNewRendezvousLocation
 Flag used to check if this robot received new rendezvous location in the it is not the consensus robot. More...
 
double aWaitingThreshold
 The maximum allowed waiting time in rendezvous location. More...
 
double aTimeWaiting
 Counter to help checking if this robot is waiting for too long. More...
 
std::shared_ptr< RendezvousPlanaPlan
 The rendezvous plan object used to control how agreements are executed, their order, and which ones to update. More...
 
std_msgs::Int8MultiArray aCommMsg
 Message to receive information from the mock communication model node. More...
 
multirobotsimulations::rendezvous aRendezvousMsg
 Message that helps the consensus robot sending new rendezvous locations to other robots. More...
 
multirobotsimulations::CustomPose aRendezvousNewPoseMsg
 Custom pose used to tell the other robots which location they should meet next with their current sub-team. More...
 
tf::Vector3 aRendezvousFootprint
 The rendezvous location this robot should go when inside a rendezous zone. More...
 
tf::Vector3 aFirstRendezvous
 Store the location of the first rendezvous location for all sub-teams. More...
 
tf::Vector3 aGoalRendezvous
 Helper variable that holds the location of the rendezvous location. More...
 
tf::Vector3 aNewRendezvousLocation
 Helper variable used to keep track where this robot should meet next with its current sub-team. More...
 
std::unique_ptr< std::mt19937 > aRandomNumberGenerator
 Random number generator for randomized social welfare. More...
 
std::random_device aRandomNumberDevice
 Random device to use with std::mt19937 to generate random numbers. More...
 
ros::Publisher aPlanRealizationPublisher
 Publisher used to help synchronize who is fulfilling a rendezvous agreement. More...
 
ros::Publisher aPlanLocationPublisher
 Publisher to broadcast new rendezvous locations for the current sub-team. More...
 

Detailed Description

Node that implements the intermittent communication policy.

While exploring, robots are going to meet at rendezvous locations spread dynamically while exploration happens. The joint-policy spreads robots when they can communicate and maximize the utility of visiting frontiers when they are alone. Robots also share maps when near each other considering a mock communication model based on communication range.

Constructor & Destructor Documentation

◆ Alysson2024Node()

Alysson2024Node::Alysson2024Node ( )

Default constructor that initializes all ros advertisers, publishers, and routines.

◆ ~Alysson2024Node()

Alysson2024Node::~Alysson2024Node ( )

Default destructor.

Member Function Documentation

◆ CanCommunicate()

bool Alysson2024Node::CanCommunicate ( const int &  id)
private

Used to check if this robot can communicate with another.

Parameters
idinteger specifying the id of the other robot.
Returns
false if it cannot communicate with the other robot, returns true otherwise.

◆ ChangeState()

void Alysson2024Node::ChangeState ( const ExplorerState newState)
private

Change the state of the robot and print information about the change.

Parameters
newStateinteger referencing the state to change to.

◆ CheckNear()

bool Alysson2024Node::CheckNear ( )
private

Used to help checking if there are other robots nearby.

This information is used to make decisions, such as where to explore.

◆ ClustersCallback()

void Alysson2024Node::ClustersCallback ( multirobotsimulations::Frontiers::ConstPtr  msg)
private

Callback for the FrontierDiscovery node to update rendezvous locations or for planning.

Parameters
msgmultirobotsimulations::Frontiers.

◆ CommCallback()

void Alysson2024Node::CommCallback ( std_msgs::Int8MultiArray::ConstPtr  msg)
private

Callback of the MockCommunication model used to check which robots are nearby.

Parameters
msgstd_msgs::Int8MultiArray.

◆ CreateMarker()

void Alysson2024Node::CreateMarker ( visualization_msgs::Marker &  input,
const char *  ns,
const int &  id,
const int &  seq 
)
private

Create a marker to mark selected goal locations (e.g., rendezvous locations or frontier clusters).

Parameters
inputvisualization_msgs::Marker of object from ROS to initialize.
nsconst char* specifying the namespace of this robot to assemble the reference frame name.
idinteger holding the unique id of this robot to assemble the reference frame name.
seqinteger holding the current marker index.

◆ CSpaceCallback()

void Alysson2024Node::CSpaceCallback ( nav_msgs::OccupancyGrid::ConstPtr  msg)
private

Callback from the MapStitching node that is used to receive meta data from the map.

Parameters
msgnav_msgs::OccupancyGrid.

◆ EstimatePoseCallback()

void Alysson2024Node::EstimatePoseCallback ( multirobotsimulations::CustomPose::ConstPtr  msg)
private

Callback for pose estimator from the SLAM algorithm.

Parameters
msgmultirobotsimulations::CustomPose.

◆ FinishedMission()

bool Alysson2024Node::FinishedMission ( )
private

Check if there are places left to explore.

Returns
false if there are places to explore, true otherwise.

◆ RandomizedFrontierSelection()

int Alysson2024Node::RandomizedFrontierSelection ( multirobotsimulations::Frontiers &  centroids,
tf::Vector3 &  selectFrontierWorld 
)
private

Select a randomized frontier.

Parameters
centroidsmultirobotsimulations::Frontiers message with all frontier clusters, their utilities, and best options.
selectFrontierWorldtf::Vector3 selected cluster.
Returns
integer index of the selected cluster.

◆ SelectFrontier()

int Alysson2024Node::SelectFrontier ( multirobotsimulations::Frontiers &  centroids,
tf::Vector3 &  selectFrontierWorld 
)
private

Select which frontier to explore from the message received by the FrontierDiscovery node.

The best frontier, the one that maximizes the utility one time step into the future, is already computed by the FrontierDiscovery node, thus saving some processing.

Parameters
centroidsmultirobotsimulations::Frontiers message holding the available frontier clusters.
selectFrontierWorldtf::Vector3 referencee to the selected cluster in the world's reference frame.
Returns
integer index of the frontier cluster that maximizes the utility one time step into the future.

◆ SelectSubteamNewRendezvous()

int Alysson2024Node::SelectSubteamNewRendezvous ( multirobotsimulations::Frontiers &  centroids,
tf::Vector3 &  selectFrontierWorld 
)
private

Select a new rendezvous location that is the frontier with the highest cost (i.e., that spread the robots the most).

Parameters
centroidsmultirobotsimulations::Frontiers message with all frontier clusters, their utilities, and best options.
selectFrontierWorldtf::Vector3 selected cluster.
Returns
integer index of the selected cluster.

◆ SetBasestationCallback()

void Alysson2024Node::SetBasestationCallback ( std_msgs::String::ConstPtr  msg)
private

Callback this node uses to go back to the basestation.

Parameters
msgstd_msgs::String message received.

◆ SetExploringCallback()

void Alysson2024Node::SetExploringCallback ( std_msgs::String::ConstPtr  msg)
private

Callback this node uses to change its internal state to start exploring.

Parameters
msgstd_msgs::String message received.

◆ SetGoal()

void Alysson2024Node::SetGoal ( const tf::Vector3 &  goal)
private

Set the goal location to visit, it could be a rendezvousl location or a frontier cluster center of mass.

Parameters
goaltf::Vector3 holding the goal location in the world reference frame.

◆ SetIdleCallback()

void Alysson2024Node::SetIdleCallback ( std_msgs::String::ConstPtr  msg)
private

Callback this node uses to stop the mission and enter in idle mode.

Parameters
msgstd_msgs::String message received.

◆ SubGoalFinishCallback()

void Alysson2024Node::SubGoalFinishCallback ( std_msgs::String::ConstPtr  msg)
private

Callback from the IntegratedGlobalPlanner node that is called when the robot reached the assigned goal.

Parameters
msgstd_msgs::String.

◆ Update()

void Alysson2024Node::Update ( )
private

Node's main update routine.

It runs the robot's state machine or policy.

Member Data Documentation

◆ aCommMsg

std_msgs::Int8MultiArray Alysson2024Node::aCommMsg
private

Message to receive information from the mock communication model node.

◆ aCSpaceMsg

nav_msgs::OccupancyGrid Alysson2024Node::aCSpaceMsg
private

Message used to store meta data from the occupancy grid to help converting world positions to positions in the grid.

◆ aCurrentState

ExplorerState Alysson2024Node::aCurrentState
private

The current state of the robot.

◆ aDeltaTime

double Alysson2024Node::aDeltaTime
private

Delta time between iterations in the main loop.

◆ aDirty

bool Alysson2024Node::aDirty
private

Used to initialize the basestation location in the main loop only once.

◆ aFirst

bool Alysson2024Node::aFirst
private

Used to skip the first delta time calculation to avoid major errors.

◆ aFirstRendezvous

tf::Vector3 Alysson2024Node::aFirstRendezvous
private

Store the location of the first rendezvous location for all sub-teams.

◆ aFrontierCentroidsMsg

multirobotsimulations::Frontiers Alysson2024Node::aFrontierCentroidsMsg
private

Message used to receive frontier clusters.

◆ aFrontierComputePublisher

ros::Publisher Alysson2024Node::aFrontierComputePublisher
private

This publisher is used to request the FrontierDiscovery module to compute new frontier clusters.

◆ aGoalBasestation

tf::Vector3 Alysson2024Node::aGoalBasestation
private

The goal position of the basestation.

◆ aGoalFrontier

tf::Vector3 Alysson2024Node::aGoalFrontier
private

Temp variable used to store which frontier this robot should explore next.

◆ aGoalPublisher

ros::Publisher Alysson2024Node::aGoalPublisher
private

This publisher is used to tell the global planner, which goal location the robot should visit next.

◆ aGoalRendezvous

tf::Vector3 Alysson2024Node::aGoalRendezvous
private

Helper variable that holds the location of the rendezvous location.

◆ aHasComm

bool Alysson2024Node::aHasComm
private

Flag used to check if the robot received the mock communication model communications array.

◆ aHasOcc

bool Alysson2024Node::aHasOcc
private

Used to known when this robot received its OccupancyGrid information from the SLAM sub-system.

◆ aHasPose

bool Alysson2024Node::aHasPose
private

Used to known when this robot received its estimate pose from the SLAM sub-system.

◆ aId

int Alysson2024Node::aId
private

Unique id.

◆ aLastTime

ros::Time Alysson2024Node::aLastTime
private

The last capatured system time used to compute the dalta time.

◆ aNamespace

std::string Alysson2024Node::aNamespace
private

The namespace of this robot.

◆ aNewRendezvousLocation

tf::Vector3 Alysson2024Node::aNewRendezvousLocation
private

Helper variable used to keep track where this robot should meet next with its current sub-team.

◆ aOccPos

Vec2i Alysson2024Node::aOccPos
private

The position of the robot in the Occupancy Grid reference frame.

◆ aPlan

std::shared_ptr<RendezvousPlan> Alysson2024Node::aPlan
private

The rendezvous plan object used to control how agreements are executed, their order, and which ones to update.

◆ aPlanLocationPublisher

ros::Publisher Alysson2024Node::aPlanLocationPublisher
private

Publisher to broadcast new rendezvous locations for the current sub-team.

◆ aPlanRealizationPublisher

ros::Publisher Alysson2024Node::aPlanRealizationPublisher
private

Publisher used to help synchronize who is fulfilling a rendezvous agreement.

◆ aQueueSize

int Alysson2024Node::aQueueSize
private

Size of all publishers and subscribers queues.

◆ aRandomNumberDevice

std::random_device Alysson2024Node::aRandomNumberDevice
private

Random device to use with std::mt19937 to generate random numbers.

◆ aRandomNumberGenerator

std::unique_ptr<std::mt19937> Alysson2024Node::aRandomNumberGenerator
private

Random number generator for randomized social welfare.

◆ aRate

int Alysson2024Node::aRate
private

Main loop rate.

◆ aReceivedNewRendezvousLocation

bool Alysson2024Node::aReceivedNewRendezvousLocation
private

Flag used to check if this robot received new rendezvous location in the it is not the consensus robot.

◆ aRendezvousFootprint

tf::Vector3 Alysson2024Node::aRendezvousFootprint
private

The rendezvous location this robot should go when inside a rendezous zone.

◆ aRendezvousMsg

multirobotsimulations::rendezvous Alysson2024Node::aRendezvousMsg
private

Message that helps the consensus robot sending new rendezvous locations to other robots.

◆ aRendezvousNewPoseMsg

multirobotsimulations::CustomPose Alysson2024Node::aRendezvousNewPoseMsg
private

Custom pose used to tell the other robots which location they should meet next with their current sub-team.

◆ aRobots

int Alysson2024Node::aRobots
private

Number of robots this robot should be aware.

◆ aSubscribers

std::vector<ros::Subscriber> Alysson2024Node::aSubscribers
private

All subscribers of this node.

Since the subscriber object is not used throughout the node, it can be stored as an array for cleaner code.

◆ aTimers

std::vector<ros::Timer> Alysson2024Node::aTimers
private

Routines of this node.

They are stored in a list format for simplicity.

◆ aTimeWaiting

double Alysson2024Node::aTimeWaiting
private

Counter to help checking if this robot is waiting for too long.

◆ aWaitingThreshold

double Alysson2024Node::aWaitingThreshold
private

The maximum allowed waiting time in rendezvous location.

If this timer is exceeded when waiting for other robots, then this robot should reset the plan and start exploring again.

◆ aWorldPos

tf::Vector3 Alysson2024Node::aWorldPos
private

The position of the robot in the world reference frame.


The documentation for this class was generated from the following file: