Skip to content

Parameters

papachric edited this page Jun 7, 2017 · 3 revisions

Estimation & Propagation Parameters

The following planner parameters correspond to the Estimation and Propagation pipelines' operation, as implemented in the rovio_bsp package (see rovio_bsp/cfg/rovio.info):

  • cam_FoVx : Horizontal Field-of-View opening of the camera sensor [deg], primarily used to evaluate Line-of-Sight visibility of locally tracked landmarks (against possible octomap occlusions) during propagation.
  • cam_FoVy : Vertical Field-of-View opening of the camera sensor [deg], primarily used to evaluate Line-of-Sight visibility of locally tracked landmarks (against possible octomap occlusions) during propagation.
  • cam_FoVz : Max range of the camera sensor [m], primarily used to evaluate Line-of-Sight visibility of locally tracked landmarks (against far-away viewpoints) during propagation.
  • map_featureVisibilityThreshold : Occlusion checking threshold when performing octomap ray-casting.
  • bsp_Ts : Forward-simulation step sampling time used during propagation [s].

(The above refer only to the additional parameters compared to the original rovio pipeline.)

Planner Parameters

The following planner parameters correspond to the volumetric_mapping process, and are loaded by the bsp_planner node in the form of ros parameters (see provided bsp_planner/launch/bsp_planner.launch):

Mapping Parameters

  • tf_frame : The mapping frame.
  • treat_unknown_as_occupied : Used for collision checking methods.
  • change_detection_enabled : Track map changes.
  • resolution : The mapping resolution.
  • visualize_min_z : MarkerArray visualization min z-coordinate.
  • visualize_max_z : MarkerArray visualization max z-coordinate.
  • sensor_max_range : Max range to consider valid measurement insertion.
  • probability_hit : Octomap hit probability.
  • probability_miss : Octomap miss probability.
  • threshold_min : Clamping threshold for min cell probability.
  • threshold_max : Clamping threshold for max cell probability.
  • threshold_occupancy : Probability threshold to consider cell as occupied.
  • map_publish_frequency : Throttled frequency to publish the map.

The following planner parameters correspond to the autonomous exploration behavior, and are loaded by the bsp_planner node from a yaml configuration file (see provided bsp_planner/cfg/bsp_settings.yaml):

System Parameters

  • system/v_max : Max translational speed [m/s] (double).
  • system/dyaw_max : Max yaw rate [rad/s] (double).
  • system/camera/pitch : Mounting pitch of the camera depth sensor [deg] (double).
  • system/camera/horizontal : Horizontal Field-of-View opening of the camera depth sensor [deg] (double).
  • system/camera/vertical : Vertical Field-of-View opening of the camera depth sensor [deg] (double).
  • system/bbx/x : Safe bounding box around vehicle for collision avoidance, x dimension [m] (double).
  • system/bbx/y : Safe bounding box around vehicle for collision avoidance, y dimension [m] (double).
  • system/bbx/z : Safe bounding box around vehicle for collision avoidance, z dimension [m] (double).
  • system/bbx/x_offset : Offset for the safe bounding box in the x dimension [m] (double).
  • system/bbx/y_offset : Offset for the safe bounding box in the y dimension [m] (double).
  • system/bbx/z_offset : Offset for the safe bounding box in the z dimension [m] (double).
  • system/bbx/overshoot : Collision-checking extension, added to the length of the sampled path segment [m] (double).

Next-Best-View (1st Planning Layer) Parameters

  • nbvp/gain/unmapped : Gain for visible Unmapped voxels, used as volumetric exploration gain (double).
  • nbvp/gain/free : Gain for visible Free voxels, used in combination with the probabilistic reobservation gain (double).
  • nbvp/gain/occupied : Gain for visible Occupied voxels, used in combination with the probabilistic reobservation gain (double).
  • nbvp/gain/probabilistic : Gain for probabilistic reobservation of already mapped (Free or Occupied) voxels (double).
  • nbvp/gain/zero : Zero-gain value, 0.0 (double).
  • nbvp/gain/range : Max camera depth sensor range - max distance of voxels to be considered for gain computation [m] (double).
  • nbvp/gain/degressive_coeff : Coefficient lambda for penalizing cumulative traveled distance when calculating gain at each node (double).
  • nbvp/gain/degressive_switchoffLoops : Number of planning loops for which the degressive penalization remains active (int).
  • nbvp/tree/extension_range : Max extension range for new RRT branches [m] (double).
  • nbvp/tree/exact_root : Start the newly sampled tree from the previous end point -true-, or from the current pose -false- (bool).
  • nbvp/tree/initial_iterations : Initial number of iterations for RRT creation (int).
  • nbvp/tree/cutoff_iterations : Cutoff number of iterations for exploration sampling, if no information gain higher than the zero-gain value has been found, sampling stops there (int).
  • nbvp/dt : Path planning time step [s] (double).

Belief-Space-Propagation (2nd Planning Layer) Parameters

  • bsp/enable : Enable/disable uncertainty-aware nested replanning layer (bool).
  • bsp/replanning_distance_min : Min edge distance of 1-st layer next-best-viewpoint to consider for replanning (double).
  • bsp/replanning_distance_ratio : Max allowed travelled distance for path replanning, given as a ratio with respect to original 1-st layer edge (double).
  • bsp/replanning_extension_ratio : Max extension range for new RRT path replanning branches, given as a ratio with respect to original 1-st layer edge (double).
  • bsp/replanning_initial_iterations : Initial number of iterations for RRT path replanning (int).
  • bsp/replanning_cutoff_iterations : Cutoff number of iterations for RRT path replanning, if no better optimality gain than the straight-transition along 1-st layer edge has has been found, sampling stops there (int).
  • bsp/replanning_gain_range : Max camera image sensor range - max distance of locally tracked landmarks to be considered visible when sampling the new path - at least 3 landmarks have to be visible from each new viewpoint (double).

Initialization Parameters

  • init/softStart : Flag to clear -mark as Free- an extended bounding box around vehicle until first successful planning iteration - used when the camera depth sensor Field-of-View is limited and the view cone does not clear enough space for collision-free planning to proceed given the system bounding box and overshoot safety thresholds (bool).
  • init/softStartMinZ : When soft start is active, allows clearing voxels only above this height level [m] (double).

Exploration Parameters

  • bbx/minX : Minimum x-coordinate value of the scenario, bounds the RRT planning [m] (double).
  • bbx/minY : Minimum y-coordinate value of the scenario, bounds the RRT planning [m] (double).
  • bbx/minZ : Minimum z-coordinate value of the scenario, bounds the RRT planning [m] (double).
  • bbx/maxX : Maximum x-coordinate value of the scenario, bounds the RRT planning [m] (double).
  • bbx/maxY : Maximum y-coordinate value of the scenario, bounds the RRT planning [m] (double).
  • bbx/maxZ : Maximum z-coordinate value of the scenario, bounds the RRT planning [m] (double).
  • bbx/explorationExtensionX : Extension for exploration along the x-coordinate, [minX-explorationExtensionX , maxX+explorationExtensionX] bounds the gain computation [m] (double).
  • bbx/explorationExtensionY : Extension for exploration along the y-coordinate, [minY-explorationExtensionY , maxY+explorationExtensionY] bounds the gain computation [m] (double).
  • bbx/explorationMinZ : Minimum z-coordinate for exploration, bounds the gain computation [m] (double).
  • bbx/explorationMaxZ : Maximum z-coordinate for exploration, bounds the gain computation [m] (double).

Visualization Parameters

  • markers/planMarker_lifetime : Visualization lifetime of MarkerArray message corresponding to the full RRT of the Next-Best-View 1st planning layer [s] (double).
  • markers/bestPlanMarker_lifetime : Visualization lifetime of MarkerArray message corresponding to the best RRT branch of the Next-Best-View 1st planning layer [s] (double).
  • markers/replanMarker_lifetime : Visualization lifetime of MarkerArray message corresponding to the full RRT of the Belief-Space-Propagation 2nd planning layer [s] (double).
  • markers/bestReplanMarker_lifetime: Visualization lifetime of MarkerArray message corresponding to the best RRT branch of the Belief-Space-Propagation 2nd planning layer [s] (double).

Mapping Parameters

  • pcl_throttle : Minimum time between subsequent pointcloud insertions [s] (double).