Particle plume C++ class. More...
#include <PPExplorer.h>
Classes | |
class | CompareSlices |
Slice of pie comparing class. More... | |
struct | SliceOfPie |
Data structure for storing slices of pie, yum! More... | |
Public Member Functions | |
bool | findClearing (geometry_msgs::PoseStamped *goal) |
Find an unexplored clearing. | |
bool | findYumiestSlice (geometry_msgs::PoseStamped *goal) |
Calculate the yumiest slice. | |
double | getExploredArea () |
Get explored area. | |
bool | isReady () |
If PPExplorer is ready to start or not. | |
bool | nextYumiestSlice (geometry_msgs::PoseStamped *goal) |
Get the nest yumiest slice. | |
PPExplorer () | |
Constructor. | |
~PPExplorer () | |
Destructor. | |
Private Member Functions | |
void | cellsCallback (const nav_msgs::GridCells::ConstPtr &msg) |
Visited cells topic callback. | |
void | chatterCallback (const pp_explorer::StringIdentified::ConstPtr &msg) |
Chatter topic callback. | |
void | explorationComplete () |
Exploration complete. | |
void | inflatedCallback (const nav_msgs::GridCells::ConstPtr &msg) |
Inflated obstacles topic callback. | |
bool | isInsidePieRadius (double x, double y, geometry_msgs::PoseStamped *robot) |
Determine if point is inside the pie radius. | |
bool | isInsideTheMap (int x, int y) |
Determine if a cell is inside the map. | |
bool | isViableGlobalMapCell (int x, int y) |
Determine if a cell is viable to go to. | |
bool | isViableLocalMapGoal (double x, double y) |
Determine if a goal is viable to go to. | |
void | mapCallback (const nav_msgs::OccupancyGrid::ConstPtr &msg) |
Map topic callback. | |
void | mapMetaCallback (const nav_msgs::MapMetaData::ConstPtr &msg) |
Map metadata topic callback. | |
void | obstaclesCallback (const nav_msgs::GridCells::ConstPtr &msg) |
Obstacles topic callback. | |
void | odomCallback (const nav_msgs::Odometry::ConstPtr &msg) |
Odometry topic callback. | |
void | posesCallback (const pp_explorer::PoseStampedIdentified::ConstPtr &msg) |
Poses topic callback. | |
void | ppCallback (const sensor_msgs::PointCloud2::ConstPtr &msg) |
Particle plume callback. | |
void | recoveryCellsCallback (const pp_explorer::GridCellsIdentified::ConstPtr &msg) |
Recovery cells topic callback. | |
void | setGoal (geometry_msgs::PoseStamped *goal) |
Set goal. | |
bool | testCell (geometry_msgs::Point *cell, std::vector< geometry_msgs::Point > *cells) |
Test cell. | |
bool | yumiestSlice (geometry_msgs::PoseStamped *goal, geometry_msgs::PoseStamped *robot_pose) |
Calculate the yumiest slice. | |
Private Attributes | |
std::list< SliceOfPie > | best_slices_ |
List of the current best slices of pie. | |
double | bubble_radius_ |
Bubble radius. | |
nav_msgs::GridCells | cells_ |
Data structure that holds the visited cells. | |
ros::Subscriber | cells_sub_ |
Visited cells topic subscriber. | |
ros::Publisher | chatter_pub_ |
Chatter pub. | |
ros::Subscriber | chatter_sub_ |
Chatter sub. | |
double | current_heading_weight_ |
Current heading weight. | |
ros::Publisher | debug_goal_pub_ |
Debug goal pub. | |
ros::Publisher | debug_pub_ |
Debug cells pub. | |
bool | debug_slices_ |
int | find_clearing_sim_steps_ |
Number of simulations. | |
bool | finish_on_next_recovery_ |
If any robot finishes it tells the other robots to stop on the next recovery behavior. | |
std::string | global_frame_id_ |
Global frame_id. | |
bool | got_map_ |
bool | got_odom_ |
nav_msgs::GridCells | inflated_ |
Data structure that holds the inflated obstacle cells. | |
ros::Subscriber | inflated_sub_ |
Inflated Obstacles topic subscriber. | |
double | inflation_radius_ |
Inflation radius. | |
nav_msgs::OccupancyGrid | map_ |
Map. | |
ros::Subscriber | map_meta_sub_ |
Map metadata topic subscriber. | |
nav_msgs::MapMetaData | map_metadata_ |
Map metadata. | |
ros::Subscriber | map_sub_ |
Map topic subscriber. | |
double | max_odor_visited_cells_coef_ |
Visited cells coefficient. | |
double | max_visited_cells_coef_ |
Visited cells coefficient. | |
int | min_particle_count_difference_ |
Minimum particle count difference. | |
bool | multi_robot_ |
If PPExplorer is working in multi robot or not. | |
ros::NodeHandle | n_ |
Node handler. | |
nav_msgs::GridCells | obstacles_ |
Data structure that holds the obstacle cells. | |
ros::Subscriber | obstacles_sub_ |
Obstacles topic subscriber. | |
message_filters::Subscriber < nav_msgs::Odometry > | odom_sub_ |
Odometry topic subscriber. | |
double | odor_weight_ |
Odor weight. | |
std::vector < pp_explorer::PoseStampedIdentified > | other_robots_poses_ |
Other robots poses on the global frame referential. | |
double | other_robots_weight_ |
Odor weight. | |
double | pie_radius_ |
pie radius. | |
int | pie_slices_ |
pie slices. | |
pcl::PointCloud< pcl::PointXYZI > | plume_ |
Particle plume data structure. | |
ros::Subscriber | plume_sub_ |
Particle plume topic publisher. | |
ros::NodeHandle | pn_ |
Private node handler. | |
ros::Publisher | poses_pub_ |
Pose pub. | |
ros::Subscriber | poses_sub_ |
Pose sub. | |
std::vector < pp_explorer::GridCellsIdentified > | recovery_cells_ |
Data structure that holds the recovery cells. | |
ros::Publisher | recovery_pub_ |
Recovery cells pub. | |
ros::Subscriber | recovery_sub_ |
Recovery cells sub. | |
geometry_msgs::PoseStamped | robot_pose_ |
Robot pose on the global frame referential. | |
tf::TransformListener | tf_ |
tf::MessageFilter < nav_msgs::Odometry > * | tf_filter_ |
std::string | unique_id_ |
Unique robot id. | |
double | visited_cells_weight_ |
Visited cells weight. |
Constructor.
Definition at line 42 of file PPExplorer.cpp.
Destructor.
Definition at line 149 of file PPExplorer.cpp.
void particle_plume::PPExplorer::cellsCallback | ( | const nav_msgs::GridCells::ConstPtr & | msg | ) | [private] |
Visited cells topic callback.
This function receives messages from the visited cells topic.
msg | Incoming nav_msgs::GridCells msg. |
Definition at line 166 of file PPExplorer.cpp.
void particle_plume::PPExplorer::chatterCallback | ( | const pp_explorer::StringIdentified::ConstPtr & | msg | ) | [private] |
Chatter topic callback.
This function receives messages from the chatter topic for multi-robot communication.
msg | Incoming pp_explorer::StringIdentified msg. |
Definition at line 262 of file PPExplorer.cpp.
void particle_plume::PPExplorer::explorationComplete | ( | ) | [private] |
Exploration complete.
Publish that exploration is complete on the chatter topic.
Definition at line 977 of file PPExplorer.cpp.
bool particle_plume::PPExplorer::findClearing | ( | geometry_msgs::PoseStamped * | goal | ) |
Find an unexplored clearing.
This function scans the map for an unexplored clearing and sets the goal to the middle of the first clearing that is found.
goal | Robot goal pose. |
Definition at line 633 of file PPExplorer.cpp.
bool particle_plume::PPExplorer::findYumiestSlice | ( | geometry_msgs::PoseStamped * | goal | ) |
Calculate the yumiest slice.
This function determines which direction the robot should take and sets a new goal.
goal | Robot goal pose. |
Definition at line 299 of file PPExplorer.cpp.
double particle_plume::PPExplorer::getExploredArea | ( | ) |
Get explored area.
Get the percentage of explored area.
Definition at line 962 of file PPExplorer.cpp.
void particle_plume::PPExplorer::inflatedCallback | ( | const nav_msgs::GridCells::ConstPtr & | msg | ) | [private] |
Inflated obstacles topic callback.
This function receives messages from the inflated obstacles topic.
msg | Incoming nav_msgs::GridCells msg. |
Definition at line 221 of file PPExplorer.cpp.
bool particle_plume::PPExplorer::isInsidePieRadius | ( | double | x, |
double | y, | ||
geometry_msgs::PoseStamped * | robot | ||
) | [private] |
Determine if point is inside the pie radius.
This helper function determines if a x y point is inside the pie radius centered at the robot pose or not.
x | Test point x coordinate. |
y | Test point y coordinate. |
robot | Robot pose. |
Definition at line 914 of file PPExplorer.cpp.
bool particle_plume::PPExplorer::isInsideTheMap | ( | int | x, |
int | y | ||
) | [private] |
Determine if a cell is inside the map.
This helper function determines if a cell is inside the map ir not.
x | Cell x. |
y | Cell y. |
Definition at line 919 of file PPExplorer.cpp.
bool particle_plume::PPExplorer::isReady | ( | ) |
If PPExplorer is ready to start or not.
Definition at line 154 of file PPExplorer.cpp.
bool particle_plume::PPExplorer::isViableGlobalMapCell | ( | int | x, |
int | y | ||
) | [private] |
Determine if a cell is viable to go to.
This helper function determines if a cell is not an obstacle, not unknown, or too close to either of the previous two.
x | Cell x. |
y | Cell y. |
Definition at line 924 of file PPExplorer.cpp.
bool particle_plume::PPExplorer::isViableLocalMapGoal | ( | double | x, |
double | y | ||
) | [private] |
Determine if a goal is viable to go to.
This helper function determines if a goal is not an obstacle, or inflated obstacle.
x | Goal x. |
y | Goal y. |
Definition at line 944 of file PPExplorer.cpp.
void particle_plume::PPExplorer::mapCallback | ( | const nav_msgs::OccupancyGrid::ConstPtr & | msg | ) | [private] |
Map topic callback.
This function receives messages from the map topic.
msg | Incoming nav_msgs::OccupancyGrid map msg. |
Definition at line 172 of file PPExplorer.cpp.
void particle_plume::PPExplorer::mapMetaCallback | ( | const nav_msgs::MapMetaData::ConstPtr & | msg | ) | [private] |
Map metadata topic callback.
This function receives messages from the map_metadata topic.
msg | Incoming nav_msgs::MapMetaData msg. |
Definition at line 179 of file PPExplorer.cpp.
bool particle_plume::PPExplorer::nextYumiestSlice | ( | geometry_msgs::PoseStamped * | goal | ) |
Get the nest yumiest slice.
This function pops the first slice in store and sets the next best heading as the robot goal. This is called when the last goal failed.
goal | Robot goal pose. |
Definition at line 622 of file PPExplorer.cpp.
void particle_plume::PPExplorer::obstaclesCallback | ( | const nav_msgs::GridCells::ConstPtr & | msg | ) | [private] |
Obstacles topic callback.
This function receives messages from the obstacles topic.
msg | Incoming nav_msgs::GridCells msg. |
Definition at line 215 of file PPExplorer.cpp.
void particle_plume::PPExplorer::odomCallback | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) | [private] |
Odometry topic callback.
This function receives messages from the odom topic.
msg | Incoming nav_msgs::Odometry msg. |
Definition at line 185 of file PPExplorer.cpp.
void particle_plume::PPExplorer::posesCallback | ( | const pp_explorer::PoseStampedIdentified::ConstPtr & | msg | ) | [private] |
Poses topic callback.
This function receives messages from the poses topic for multi-robot communication.
msg | Incoming pp_explorer::PoseStampedIdentified msg. |
Definition at line 271 of file PPExplorer.cpp.
void particle_plume::PPExplorer::ppCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) | [private] |
Particle plume callback.
This function receives messages from the plume topic.
msg | Incoming pcl::PointCloud<pcl::PointXYZI> msg. |
Definition at line 160 of file PPExplorer.cpp.
void particle_plume::PPExplorer::recoveryCellsCallback | ( | const pp_explorer::GridCellsIdentified::ConstPtr & | msg | ) | [private] |
Recovery cells topic callback.
This function receives messages from the recovery cells topic.
msg | Incoming pp_explorer::GridCellsIdentified msg. |
Definition at line 227 of file PPExplorer.cpp.
void particle_plume::PPExplorer::setGoal | ( | geometry_msgs::PoseStamped * | goal | ) | [private] |
Set goal.
This function sets a goal to the robot from the current yumiest slice.
goal | Robot goal pose. |
Definition at line 884 of file PPExplorer.cpp.
bool particle_plume::PPExplorer::testCell | ( | geometry_msgs::Point * | cell, |
std::vector< geometry_msgs::Point > * | cells | ||
) | [private] |
Test cell.
This is a helper function for findClearing and it test for a cell inside a vector of cells.
cell | The cell to be tested. |
cells | The vector of cells to be tested. |
Definition at line 873 of file PPExplorer.cpp.
bool particle_plume::PPExplorer::yumiestSlice | ( | geometry_msgs::PoseStamped * | goal, |
geometry_msgs::PoseStamped * | robot_pose | ||
) | [private] |
Calculate the yumiest slice.
This function determines which direction the robot should take and sets a new goal.
Definition at line 304 of file PPExplorer.cpp.
std::list<SliceOfPie> particle_plume::PPExplorer::best_slices_ [private] |
List of the current best slices of pie.
Definition at line 281 of file PPExplorer.h.
double particle_plume::PPExplorer::bubble_radius_ [private] |
Bubble radius.
The radius of the bubble used to count particles during odor gradient extraction
Definition at line 266 of file PPExplorer.h.
nav_msgs::GridCells particle_plume::PPExplorer::cells_ [private] |
Data structure that holds the visited cells.
Definition at line 190 of file PPExplorer.h.
Visited cells topic subscriber.
Definition at line 140 of file PPExplorer.h.
Chatter pub.
Definition at line 161 of file PPExplorer.h.
Chatter sub.
Definition at line 159 of file PPExplorer.h.
double particle_plume::PPExplorer::current_heading_weight_ [private] |
Current heading weight.
The weight given to the robot's current heading in the cost function.
Definition at line 250 of file PPExplorer.h.
Debug goal pub.
Definition at line 181 of file PPExplorer.h.
Debug cells pub.
Definition at line 179 of file PPExplorer.h.
bool particle_plume::PPExplorer::debug_slices_ [private] |
Definition at line 183 of file PPExplorer.h.
int particle_plume::PPExplorer::find_clearing_sim_steps_ [private] |
Number of simulations.
Number of simulations performed during the find clearing stage.
Definition at line 234 of file PPExplorer.h.
bool particle_plume::PPExplorer::finish_on_next_recovery_ [private] |
If any robot finishes it tells the other robots to stop on the next recovery behavior.
Definition at line 174 of file PPExplorer.h.
std::string particle_plume::PPExplorer::global_frame_id_ [private] |
Global frame_id.
Definition at line 206 of file PPExplorer.h.
bool particle_plume::PPExplorer::got_map_ [private] |
Definition at line 456 of file PPExplorer.h.
bool particle_plume::PPExplorer::got_odom_ [private] |
Definition at line 457 of file PPExplorer.h.
nav_msgs::GridCells particle_plume::PPExplorer::inflated_ [private] |
Data structure that holds the inflated obstacle cells.
Definition at line 200 of file PPExplorer.h.
Inflated Obstacles topic subscriber.
Definition at line 147 of file PPExplorer.h.
double particle_plume::PPExplorer::inflation_radius_ [private] |
Inflation radius.
The inflation radius used by the navigation stack.
Definition at line 239 of file PPExplorer.h.
nav_msgs::OccupancyGrid particle_plume::PPExplorer::map_ [private] |
Map.
Definition at line 193 of file PPExplorer.h.
Map metadata topic subscriber.
Definition at line 138 of file PPExplorer.h.
nav_msgs::MapMetaData particle_plume::PPExplorer::map_metadata_ [private] |
Map metadata.
Definition at line 195 of file PPExplorer.h.
Map topic subscriber.
Definition at line 136 of file PPExplorer.h.
double particle_plume::PPExplorer::max_odor_visited_cells_coef_ [private] |
Visited cells coefficient.
This coefficient gives the weight given to the number of visited cells during when odor is present, should be higher than max_visited_cells_coef.
Definition at line 229 of file PPExplorer.h.
double particle_plume::PPExplorer::max_visited_cells_coef_ [private] |
Visited cells coefficient.
This coefficient gives the weight given to the number of visited cells.
Definition at line 222 of file PPExplorer.h.
Minimum particle count difference.
The minimum particle count difference allowed for an odor gradient to be considered.
Definition at line 271 of file PPExplorer.h.
bool particle_plume::PPExplorer::multi_robot_ [private] |
If PPExplorer is working in multi robot or not.
Definition at line 151 of file PPExplorer.h.
Node handler.
Definition at line 128 of file PPExplorer.h.
nav_msgs::GridCells particle_plume::PPExplorer::obstacles_ [private] |
Data structure that holds the obstacle cells.
Definition at line 198 of file PPExplorer.h.
Obstacles topic subscriber.
Definition at line 145 of file PPExplorer.h.
message_filters::Subscriber<nav_msgs::Odometry> particle_plume::PPExplorer::odom_sub_ [private] |
Odometry topic subscriber.
Definition at line 132 of file PPExplorer.h.
double particle_plume::PPExplorer::odor_weight_ [private] |
Odor weight.
The weight given to the odor presence in the cost function.
Definition at line 255 of file PPExplorer.h.
std::vector<pp_explorer::PoseStampedIdentified> particle_plume::PPExplorer::other_robots_poses_ [private] |
Other robots poses on the global frame referential.
Definition at line 171 of file PPExplorer.h.
double particle_plume::PPExplorer::other_robots_weight_ [private] |
Odor weight.
The weight given to the heading in regard to the other robots in the cost function.
Definition at line 260 of file PPExplorer.h.
double particle_plume::PPExplorer::pie_radius_ [private] |
pie radius.
The pie radius determines the radius around the robot for which viable paths will be calculated.
Definition at line 212 of file PPExplorer.h.
int particle_plume::PPExplorer::pie_slices_ [private] |
pie slices.
The number of pie slices determines the number of paths that will be considered.
Definition at line 217 of file PPExplorer.h.
pcl::PointCloud<pcl::PointXYZI> particle_plume::PPExplorer::plume_ [private] |
Particle plume data structure.
Definition at line 187 of file PPExplorer.h.
Particle plume topic publisher.
Definition at line 142 of file PPExplorer.h.
Private node handler.
Definition at line 130 of file PPExplorer.h.
Pose pub.
Definition at line 165 of file PPExplorer.h.
Pose sub.
Definition at line 163 of file PPExplorer.h.
std::vector<pp_explorer::GridCellsIdentified> particle_plume::PPExplorer::recovery_cells_ [private] |
Data structure that holds the recovery cells.
Definition at line 168 of file PPExplorer.h.
Recovery cells pub.
Definition at line 157 of file PPExplorer.h.
Recovery cells sub.
Definition at line 155 of file PPExplorer.h.
geometry_msgs::PoseStamped particle_plume::PPExplorer::robot_pose_ [private] |
Robot pose on the global frame referential.
Definition at line 203 of file PPExplorer.h.
Definition at line 133 of file PPExplorer.h.
tf::MessageFilter<nav_msgs::Odometry>* particle_plume::PPExplorer::tf_filter_ [private] |
Definition at line 134 of file PPExplorer.h.
std::string particle_plume::PPExplorer::unique_id_ [private] |
Unique robot id.
Definition at line 153 of file PPExplorer.h.
double particle_plume::PPExplorer::visited_cells_weight_ [private] |
Visited cells weight.
The weight given to the ammount of visited cells in the cost function.
Definition at line 245 of file PPExplorer.h.