Only released in EOL distros:  

Overview

PPExplorer is a an odor oriented exploration algorithm that builds on top of the odor mapping package particle_plume.

The PPE algorithm is in charge of odor oriented exploration and plume tracking. This is accomplished in four steps. (1) Initially a circle of radius r is drawn around the robot and divided into n slices. (2) Next the slices which overlap with obstacles are removed. (3) The slices which contain a percentage of explored area over a certain threshold are then also removed. (4) Finally the cost of each remaining slice is calculated using a cost function. The slice with the lowest cost is chosen and the goal is set. The variables used fore the cost function are the amount of explored area, the angular distance to the odor gradient and the angular distance to the current heading of the robot.

ppexplorer.jpg

ROS API

pp_explorer_node

pp_explorer_node is an odor oriented exploration and plume tracking algorithm.

Subscribed Topics

odom (nav_msgs/Odometry)
  • Robot odometry.
/map (nav_msgs/OccupancyGrid)
  • Global map.
/map_metadata (nav_msgs/MapMetaData)
  • Global map metadata.
/visited_cells (nav_msgs/GridCells)
  • Visited cells from particle_plume.
/plume (sensor_msgs/PointCloud2)
  • The odor plume from particle_plume.
move_base/local_costmap/obstacles (nav_msgs/GridCells)
  • Obstacles from the navigation stack.
move_base/local_costmap/inflated_obstacles (nav_msgs/GridCells)
  • Inflated obstacles from the navigation stack.

Published Topics

debug_cells (nav_msgs/GridCells)
  • This allows to visually debug the slices.
pp_goal (visualization_msgs/Marker)
  • This allows to visually debug the goals.

Parameters

~global_frame_id (string, default: map)
  • The global frame id.
~max_visited_cells_coef (double, default: 0.35)
  • The maximum visited cells coefficient allowed for a slice to be considered. This must be a value between 0 and 1.
~max_odor_visited_cells_coef (double, default: 0.50)
  • The maximum visited cells coefficient allowed for a slice to be considered when odor is present. This must be a value between 0 and 1.
~pie_radius (double, default: 0.60)
  • The radius of the pie laid around the robot.
~pie_slices (int, default: 16)
  • The number of slices inside the pie. This value cannot be lower than 4.
~find_clearing_sim_steps (int, default: 3)
  • The number of simulations pp_explorer must be able to successfully complete to set a goal during the recovery behavior.
~visited_cells_weight (double, default: 1.00)
  • The weight given to the visited cells in the cost function.
~current_heading_weight (double, default: 0.01)
  • The weight given to the current heading of the robot in the cost function.
~odor_weight (double, default: 0.10)
  • The weight given to the odor gradient in the cost function.
~bubble_radius (double, default: 0.10)
  • The radius of the bubble used to sample the plume for calculating the odor gradient.
~min_particle_count_difference (int, default: 5)
  • The minimum difference between the maximum and minimum particle count inside the plume to consider an odor gradient.
~move_base/local_costmap/inflation_radius (double, default: 0.20)
  • The inflation radius used by the navigation stack.
~debug_slices (bool, default: false)
  • If true the debug mode will be on and the topics debug_cells and pp_goal will be published to.

Tutorials

Coming soon...

Wiki: pp_explorer (last edited 2011-04-18 13:40:26 by Gonçalo Cabrita)