Skip to content

A parameterized map generator for planning evaluations and benchmarking

License

Notifications You must be signed in to change notification settings

KumarRobotics/kr_param_map

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

44 Commits
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

Kumar Lab Parameterized Map

All in one! It's a revolution in map parameterization and representation for motion planning.

About

This repo is related to our evaluation research. If this repo helps your research, please cite our paper at:

@INPROCEEDINGS{10610207,
  author={Shao, Yifei Simon and Wu, Yuwei and Jarin-Lipschitz, Laura and Chaudhari, Pratik and Kumar, Vijay},
  booktitle={2024 IEEE International Conference on Robotics and Automation (ICRA)}, 
  title={Design and Evaluation of Motion Planners for Quadrotors in Environments with Varying Complexities}, 
  year={2024},
  volume={},
  number={},
  pages={10033-10039},
  keywords={Measurement;Navigation;Software algorithms;Kinematics;Planning;Complexity theory;Trajectory},
  doi={10.1109/ICRA57147.2024.10610207}}

0. Setup

0.1 General map annotation

0.2 Prerequisites

  • Follow the guidance to install ROS Noetic

  • You might encounter package issues for SDL. Please install SDL version 1.x

sudo apt install libsdl1.2-dev libsdl-image1.2-dev

1. Usage

In your "${YOUR_WORKSPACE_PATH}/src",

git clone git@github.com:KumarRobotics/kr_param_map.git
cd ../..
catkin b
source devel/setup.bash

1.1 Grid Map Reader

Set the map mode and file path in "read_grid_map.launch" and launch

roslaunch param_env read_grid_map.launch

We support file format as:

  • image map: .png
  • rosbag: sensor_msgs::PointCloud
  • rosbag: sensor_msgs::PointCloud2
  • pcd

In the launch file, set "map/mode" to switch to a different mode, and use the following examples to load the map.

<!-- map mode 
       0 randomly generate
       1 read the image
       2 read the ros bag poind cloud 1
       3 read the ros bag poind cloud 2
       4 read pcd file -->
<param name="map/mode"       value="4" />

We also enable multi-map loading, set folder path, and use_folder as true. If you only want to load a single file, please comment the following:

<param name="folder_path" value="$(find param_env)/data/img/maze/"/>
<param name="use_folder"  value="false"/>
  • The 2D image map is converted into 3d, with z-axis having the same content.

  • Maze images are generated with the help of Multi Solution Maze Generator

The point cloud in bags is shown as:

You can also set the inflation (m) to inflate the grid map

<param name="map/inflate_radius" value="0.3"/>

The topics:

  • /read_grid_map/global_cloud: publish the point clouds
  • /read_grid_map/global_gridmap: publish the center points of the grid map with inflation

1.2 Sctructed Map Generator

roslaunch param_env structure_map.launch

You can adjust the approximate ratio of each element (overlapping is also counting now) in the launch file

<param name="map/cylinder_ratio" value="0.10" type="double"/>
<param name="map/circle_ratio"   value="0.02" type="double"/>
<param name="map/gate_ratio"     value="0.02" type="double"/>
<param name="map/ellip_ratio"    value="0.02" type="double"/>
<param name="map/poly_ratio"     value="0.01" type="double"/>

Examples:

By increasing the occupied ratios, it's harder to generate feasible trajectories.

You can also enable noise around the obstacles by setting:

  <param name="params/add_noise" value="true"/>

The topics:

  • /structure_map/global_cloud: publish the point clouds

1.3 Change resolution or change map

You can also change the resolution online by publishing the resolution value to:

/structure_map/change_res

or

/read_grid_map/change_res

For read maps, you can publish all the maps by setting the folder path in the launch file.

 <param name="folder_path" value="$(find param_env)/data/img/maze/"/>

Publish true in topic.

/structure_map/change_map

or

/read_grid_map/change_map

to trigger the function.

1.4 Dataset generation

If you want to save map, set "dataset/save_map" to true, and set the data number in "dataset/samples_num".

    <param name="dataset/save_map"    value="true"/>
    <param name="dataset/samples_num" value="100"/>
    <param name="dataset/start_index" value="5080900"/>
    <param name="dataset/path"        value="$(find param_env)/dataset/"/>

It will be saved into the path you set.

About

A parameterized map generator for planning evaluations and benchmarking

Topics

Resources

License

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Contributors 3

  •  
  •  
  •