Skip to content

Parameters in FIESTA Node

hlx1996 edited this page Jun 28, 2019 · 8 revisions

There are two types of parameters in FIESTA. Some are inside the code, which needs to direct modify code and re-compile it. It is not a good manner and will be refined in the future. Others are written in the launch file, which can be easily modified to change the parameters.

Written Inside the code

  1. In test_fiesta.cpp
    • At this line, you can choose the types of depth map message and pose message.
  • Type of Depth Map Message is chosen from [sensor_msgs::PointCloud2::ConstPtr, sensor_msgs::Image::ConstPtr]
  • Type of Pose Message is chosen from [geometry_msgs::PoseStamped::ConstPtr, nav_msgs::Odometry::ConstPtr, geometry_msgs::TransformStamped::ConstPtr]
  1. In parameters.h
  • At this line, choose whether to use probabilistic or deterministic occupancy grid map
  • At these lines, choose whether to use array implementation, hash table implementation or hash table with blocks, and the number of voxels inside a block can be modified here, by parameters called block_bit_ or block_, depends on whether the bitwise operations are used or not.
  • At these lines, choose the configuration of the neighborhood by parameters dirs_ and num_dirs_
  1. In parameters.cpp
  • At these lines to modify two transformations, useful when you are using data set not captured by yourself.
  • T_D_B: A static transformation from the dynamic to the base system that will be applied.
  • T_B_C: A static transformation from the base to the sensor that will be applied.

Written in the launch file

Basic Parameters

  • resolution: the resolution of Occupancy Grid Map & ESDF Map
  • update_esdf_every_n_sec: Update Frequency in seconds
  • If Hash Table implementation is used
    • reserved_size: Reserved Size of Hash Table, for I am using a vector-like array to implement a hash table
  • If Array implementation is used
    • lx, ly, lz, rx, ry, rz: The border of the map

Raycasting Parameters

  • min_ray_length, max_ray_length: The minimum and the maximum distance of ray.
  • ray_cast_num_thread: Threads used to be multi-thread. If the hash table is used, make sure the value is 0. In array implementation, 0 means no other thread. <- This may have bugs now.

Probabilistic Occupancy Grid Map Parameters

  • Parameters are p_hit, p_miss, p_min, p_max and p_occ
  • Inside the code probabilistic of occupancy is represented as Logit Probability, i.e. $logit(p) = \log\dfrac{p}{1 - p}$.
  • If observed once, $p \leftarrow \min{(p + p_hit), p_max}$.
  • If missed once, $p \leftarrow \max{(p + p_miss), p_min}$.
  • The grid is considered occupied iff $p \geq p_occ$.

Global and Local Map

  • global_map: Determine everything, including local update, visualization, and remove the previous information.
  • global_update: Determine to update globally or locally.
  • global_vis: Only to determine to visualize globally or locally.
  • radius_x, radius_y, radius_z: Radius of the local range

Depth Image Parameters

  • center_x, center_y, focal_x, focal_y: Camera Intrinsic Parameters
  • use_depth_filter: Whether to use depth filter or not
  • depth_filter_tolerance: Maximum tolerance of inconsistency between the consecutive two frames
  • depth_filter_min_dist, depth_filter_max_dist: The minimum and maximum distance of Depth Image Value not to be filtered
  • depth_filter_margin: Filter margin, in the pixel unit

Visualization

  • visualize_every_n_updates: Visualization frequency base on the numbers of updates, 0 for no visualization
  • slice_vis_max_dist: Assume the Maximum distance we want to visualize, above which shows the same color, while the actual data in the variable is not constant
  • The following two is based on lz if the array is used, relative to the 0 if the hash table is used
  • slice_vis_level: The level of the slice of ESDF Map to be shown
  • vis_lower_bound, vis_upper_bound: The lower and upper bound of the Z-axis of the visualization of Occupancy Grid Map

Subscribe source

  • depth, transform represents depth map message and pose message respectively.