![]() |
Multi-robot Playground
|
Node that implements the intermittent communication policy. More...
#include <Alysson2024Node.h>
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 ¢roids, 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 ¢roids, tf::Vector3 &selectFrontierWorld) |
Select a randomized frontier. More... | |
int | SelectSubteamNewRendezvous (multirobotsimulations::Frontiers ¢roids, 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< RendezvousPlan > | aPlan |
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... | |
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.
Alysson2024Node::Alysson2024Node | ( | ) |
Default constructor that initializes all ros advertisers, publishers, and routines.
Alysson2024Node::~Alysson2024Node | ( | ) |
Default destructor.
|
private |
Used to check if this robot can communicate with another.
id | integer specifying the id of the other robot. |
|
private |
Change the state of the robot and print information about the change.
newState | integer referencing the state to change to. |
|
private |
Used to help checking if there are other robots nearby.
This information is used to make decisions, such as where to explore.
|
private |
Callback for the FrontierDiscovery node to update rendezvous locations or for planning.
msg | multirobotsimulations::Frontiers. |
|
private |
Callback of the MockCommunication model used to check which robots are nearby.
msg | std_msgs::Int8MultiArray. |
|
private |
Create a marker to mark selected goal locations (e.g., rendezvous locations or frontier clusters).
input | visualization_msgs::Marker of object from ROS to initialize. |
ns | const char* specifying the namespace of this robot to assemble the reference frame name. |
id | integer holding the unique id of this robot to assemble the reference frame name. |
seq | integer holding the current marker index. |
|
private |
Callback from the MapStitching node that is used to receive meta data from the map.
msg | nav_msgs::OccupancyGrid. |
|
private |
Callback for pose estimator from the SLAM algorithm.
msg | multirobotsimulations::CustomPose. |
|
private |
Check if there are places left to explore.
|
private |
Select a randomized frontier.
centroids | multirobotsimulations::Frontiers message with all frontier clusters, their utilities, and best options. |
selectFrontierWorld | tf::Vector3 selected cluster. |
|
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.
centroids | multirobotsimulations::Frontiers message holding the available frontier clusters. |
selectFrontierWorld | tf::Vector3 referencee to the selected cluster in the world's reference frame. |
|
private |
Select a new rendezvous location that is the frontier with the highest cost (i.e., that spread the robots the most).
centroids | multirobotsimulations::Frontiers message with all frontier clusters, their utilities, and best options. |
selectFrontierWorld | tf::Vector3 selected cluster. |
|
private |
Callback this node uses to go back to the basestation.
msg | std_msgs::String message received. |
|
private |
Callback this node uses to change its internal state to start exploring.
msg | std_msgs::String message received. |
|
private |
Set the goal location to visit, it could be a rendezvousl location or a frontier cluster center of mass.
goal | tf::Vector3 holding the goal location in the world reference frame. |
|
private |
Callback this node uses to stop the mission and enter in idle mode.
msg | std_msgs::String message received. |
|
private |
Callback from the IntegratedGlobalPlanner node that is called when the robot reached the assigned goal.
msg | std_msgs::String. |
|
private |
Node's main update routine.
It runs the robot's state machine or policy.
|
private |
Message to receive information from the mock communication model node.
|
private |
Message used to store meta data from the occupancy grid to help converting world positions to positions in the grid.
|
private |
The current state of the robot.
|
private |
Delta time between iterations in the main loop.
|
private |
Used to initialize the basestation location in the main loop only once.
|
private |
Used to skip the first delta time calculation to avoid major errors.
|
private |
Store the location of the first rendezvous location for all sub-teams.
|
private |
Message used to receive frontier clusters.
|
private |
This publisher is used to request the FrontierDiscovery module to compute new frontier clusters.
|
private |
The goal position of the basestation.
|
private |
Temp variable used to store which frontier this robot should explore next.
|
private |
This publisher is used to tell the global planner, which goal location the robot should visit next.
|
private |
Helper variable that holds the location of the rendezvous location.
|
private |
Flag used to check if the robot received the mock communication model communications array.
|
private |
Used to known when this robot received its OccupancyGrid information from the SLAM sub-system.
|
private |
Used to known when this robot received its estimate pose from the SLAM sub-system.
|
private |
Unique id.
|
private |
The last capatured system time used to compute the dalta time.
|
private |
The namespace of this robot.
|
private |
Helper variable used to keep track where this robot should meet next with its current sub-team.
|
private |
The position of the robot in the Occupancy Grid reference frame.
|
private |
The rendezvous plan object used to control how agreements are executed, their order, and which ones to update.
|
private |
Publisher to broadcast new rendezvous locations for the current sub-team.
|
private |
Publisher used to help synchronize who is fulfilling a rendezvous agreement.
|
private |
Size of all publishers and subscribers queues.
|
private |
Random device to use with std::mt19937 to generate random numbers.
|
private |
Random number generator for randomized social welfare.
|
private |
Main loop rate.
|
private |
Flag used to check if this robot received new rendezvous location in the it is not the consensus robot.
|
private |
The rendezvous location this robot should go when inside a rendezous zone.
|
private |
Message that helps the consensus robot sending new rendezvous locations to other robots.
|
private |
Custom pose used to tell the other robots which location they should meet next with their current sub-team.
|
private |
Number of robots this robot should be aware.
|
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.
|
private |
Routines of this node.
They are stored in a list format for simplicity.
|
private |
Counter to help checking if this robot is waiting for too long.
|
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.
|
private |
The position of the robot in the world reference frame.