GithubHelp home page GithubHelp logo

hkust-aerial-robotics / predrecon Goto Github PK

View Code? Open in Web Editor NEW
149.0 9.0 10.0 71.38 MB

A Prediction-boosted Planner for Fast and High-quality Autonomous Aerial Reconstruction

License: GNU General Public License v3.0

Python 11.59% Cuda 1.78% C++ 55.22% CMake 2.78% C 22.93% Shell 0.01% Makefile 0.01% Common Lisp 5.68%
motion-planning aerial-imagery aerial-robotics aerial-reconstruction

predrecon's Introduction

PredRecon

News

  • 20/06/2023: The code of Hierarchical Planner is available.
  • 06/06/2023: The simulator (AirSim) is available.
  • 10/02/2023: The code of Surface Prediction Module (SPM) is available.

Introduction

[ICRA'23] This repository maintains the implementation of "PredRecon: A Prediction-boosted Planning Framework for Fast and High-quality Autonomous Aerial Reconstruction".

Paper: arXiv, IEEE

Complete video: Video

Authors: Chen Feng, Haojia Li, Fei Gao, Boyu Zhou, and Shaojie Shen.

Institutions: HKUST Aerial Robotics Group, SYSU STAR Group, and ZJU FASTLab.

Please cite our paper if you use this project in your research:

@inproceedings{feng2023predrecon,
  title={PredRecon: A Prediction-boosted Planning Framework for Fast and High-quality Autonomous Aerial Reconstruction},
  author={Feng, Chen and Li, Haojia and Gao, Fei and Zhou, Boyu and Shen, Shaojie},
  booktitle={2023 IEEE International Conference on Robotics and Automation (ICRA)},
  pages={1207-1213},
  year={2023},
  organization={IEEE}
}

PredRecon is a prediction-boosted planning framework that can efficiently reconstruct high-quality 3D models for the target areas in unknown environments with a single flight. We obtain inspiration from humans can roughly infer the complete construction structure from partial observation. Hence, we devise a surface prediction module (SPM) to predict the coarse complete surfaces of the target from current partial reconstruction. Then, the uncovered surfaces are produced by online volumetric mapping waiting for the observation by UAV. Lastly, a hierarchical planner plans motions for 3D reconstruction, which sequentially find efficient global coverage paths, plans local paths for maximizing the performance of Multi-View Stereo (MVS) and generate smooth trajectories for image-pose pairs acquisition. We conduct benchmark in the realistic simulator, which validates the performance of PredRecon compared with classical and state-of-the-art methods.

Please kindly star โญ๏ธ this project if it helps you. We take great efforts to develop and maintain it ๐Ÿ˜.

Installation

The project has been tested on Ubuntu 20.04 LTS (ROS Noetic). Directly clone our package (using ssh here):

  cd ${YOUR_WORKSPACE_PATH}/src
  git clone https://github.com/HKUST-Aerial-Robotics/PredRecon.git

Then install individual components of PredRecon:

  • To install Surface Prediction Module, please follow the steps in SPM.
  • To install Hierarchical Planner, please follow the steps in Planner.

Quick Start

You can decide whether saving captured images by changing the parameter reconfsm/img_flag in algorithm.xml, where true for saving and false for not saving. Note: If you set such parameter as true, all captured images will be saved in reconfsm/img_dir_, which can be changed to your own path in algorithm.xml.

Open your Unreal Engine platform, then run AirSim simulator in the terminal:

  source devel/setup.zsh && roslaunch airsim_ros_pkgs airsim_node.launch

Firstly, run Rviz for trajectory visualization:

  source devel/setup.zsh && roslaunch exploration_manager rviz.launch

Then, run the simulation:

  source devel/setup.zsh && roslaunch exploration_manager recon.launch

Trigger the quadrotor to start flight for collecting information by the 2D Nav Goal tool in Rviz.

After the flight, all images-pose pairs captured is stored in your given folder. We recommend RealityCapture or COLMAP as the 3D reconstruction platform. If you want to uae COLMAP in your terminal, you can follow the usage example in COLMAP Usage.

Known Issues

You can simply verify whether your AirSim is working properly

  source devel/setup.zsh && roslaunch airsim_ros_pkgs airsim_node.launch
  source devel/setup.zsh && roslaunch exploration_manager rviz.launch
  source devel/setup.zsh && roslaunch exploration_manager init_test.launch

If AirSim is working correctly, you will see the initial flight of the drone and the mapping results in both AirSim and Rviz.

Acknowledgements

We use NLopt for non-linear optimization, use LKH for travelling salesman problem, and thank the source code of mmdetection3d and FUEL.

predrecon's People

Contributors

chen-albert-feng avatar zbylgsc avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

predrecon's Issues

The trajectory cannot be planned when running PredRecon

At present, I have encountered some problems in the recurrence process, and I hope to get your answers:

  1. Open Rviz and you can see the depth interface, but the main interface displays blank without the predicted point cloud. Is this normal?

I think depthmap needs to be processed by SPM to predict the surface information of objects, but I have not seen the visual interface and output results at present. At present, I do not train the model, and I directly use the spm.pt published by you.

  1. When I started the recon.launch and passed the 2D Nav trigger in Rviz, the terminal displayed the following information (see attachment), and the aircraft did not move in the simulation environment.

Sometimes it is exported

Replan: collision detected

I'm not sure how to solve it, please give me some suggestions.

The following is my terminal output

... logging to /home/rc/.ros/log/738f66a8-820d-11ee-84fa-3328690ce210/roslaunch-rc-40178.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://rc:45041/

SUMMARY
========

PARAMETERS
 * /exploration_node/astar/allocate_num: 1000000
 * /exploration_node/astar/lambda_heu: 10000.0
 * /exploration_node/astar/lambda_heu_global: 100000.0
 * /exploration_node/astar/max_search_time: 0.005
 * /exploration_node/astar/resolution_astar: 0.2
 * /exploration_node/bspline/limit_acc: 0.8
 * /exploration_node/bspline/limit_ratio: 1.1
 * /exploration_node/bspline/limit_vel: 0.8
 * /exploration_node/exploration/am: 0.8
 * /exploration_node/exploration/max_decay: 0.8
 * /exploration_node/exploration/refine_local: True
 * /exploration_node/exploration/refined_num: 7
 * /exploration_node/exploration/refined_radius: 5.0
 * /exploration_node/exploration/relax_time: 1.0
 * /exploration_node/exploration/top_view_num: 15
 * /exploration_node/exploration/tsp_dir: /home/rc/Projects...
 * /exploration_node/exploration/vm: 0.8
 * /exploration_node/exploration/w_dir: 1.5
 * /exploration_node/exploration/yd: 0.5235987666666666
 * /exploration_node/exploration/ydd: 0.5235987666666666
 * /exploration_node/frontier/candidate_dphi: 0.2617993833333333
 * /exploration_node/frontier/candidate_rmax: 2.5
 * /exploration_node/frontier/candidate_rmin: 1.5
 * /exploration_node/frontier/candidate_rnum: 3
 * /exploration_node/frontier/cluster_min: 100
 * /exploration_node/frontier/cluster_size_xy: 2.0
 * /exploration_node/frontier/cluster_size_z: 10.0
 * /exploration_node/frontier/down_sample: 3
 * /exploration_node/frontier/min_candidate_clearance: 0.21
 * /exploration_node/frontier/min_candidate_dist: 0.75
 * /exploration_node/frontier/min_view_finish_fraction: 0.2
 * /exploration_node/frontier/min_visib_num: 15
 * /exploration_node/fsm/replan_time: 0.2
 * /exploration_node/fsm/thresh_replan1: 0.5
 * /exploration_node/fsm/thresh_replan2: 0.5
 * /exploration_node/fsm/thresh_replan3: 1.5
 * /exploration_node/global/cluster_pca_diameter_: 0.6
 * /exploration_node/global/consistency_cost_: 5.0
 * /exploration_node/global/dist_cost_: 0.5
 * /exploration_node/global/downsample_coeff_: 1.0
 * /exploration_node/global/downsample_each_: 10.0
 * /exploration_node/global/nbv_distlb_: 4.0
 * /exploration_node/global/nbv_distub_: 6.5
 * /exploration_node/global/normal_judge_param_: 0.8
 * /exploration_node/global/projection_param_: 0.0005
 * /exploration_node/global/sample_angle_step_: 1.0471975333333332
 * /exploration_node/global/sample_min_dist_: 0.75
 * /exploration_node/global/sample_phi_range_: 0.17453292222222222
 * /exploration_node/global/sample_r_max_: 6.7
 * /exploration_node/global/sample_r_min_: 6.5
 * /exploration_node/global/sample_r_num_: 2
 * /exploration_node/global/sample_theta_threshold_: 0.8726646111111112
 * /exploration_node/global/sample_z_num_: 1
 * /exploration_node/global/sample_z_range_: 4.0
 * /exploration_node/global/sample_z_size_: 0.1
 * /exploration_node/global/tsp_dir_: /home/rc/Projects...
 * /exploration_node/global/tsp_max_decay_: 0.8
 * /exploration_node/global/tsp_refine_num_: 20
 * /exploration_node/global/tsp_refine_radius_: 10.0
 * /exploration_node/global/tsp_topvp_num_: 5
 * /exploration_node/global/uniform_grid_size_: 5.0
 * /exploration_node/global/visible_threshold_: 0.1
 * /exploration_node/heading_planner/half_vert_num: 5
 * /exploration_node/heading_planner/lambda1: 2.0
 * /exploration_node/heading_planner/lambda2: 1.0
 * /exploration_node/heading_planner/max_yaw_rate: 0.17453292222222222
 * /exploration_node/heading_planner/w: 20000.0
 * /exploration_node/heading_planner/weight_type: 1.0
 * /exploration_node/heading_planner/yaw_diff: 0.5235987666666666
 * /exploration_node/local/cluster_pca_diameter_: 0.4
 * /exploration_node/local/downsample_factor_: 1.0
 * /exploration_node/local/interval: 1.5
 * /exploration_node/local/local_normal_threshold: 0.8726646111111112
 * /exploration_node/local/normal_length_: 0.8
 * /exploration_node/local/region_max_size_: 3.0
 * /exploration_node/local/tsp_dir_: /home/rc/Projects...
 * /exploration_node/local/vp_angle_step_: 0.2617993833333333
 * /exploration_node/local/vp_max_radius_: 6.7
 * /exploration_node/local/vp_min_radius_: 6.5
 * /exploration_node/local/vp_phi_range_: 0.2617993833333333
 * /exploration_node/local/vp_pseudo_bias_: 0.19198621444444444
 * /exploration_node/local/vp_r_num_: 1
 * /exploration_node/local/vp_theta_upper_: 0.8726646111111112
 * /exploration_node/local/vp_visible_threshold_: 0.3
 * /exploration_node/local/vp_z_num_: 2
 * /exploration_node/local/vp_z_range_: 2.0
 * /exploration_node/local/vp_z_size_: 2.0
 * /exploration_node/manager/clearance_threshold: 0.2
 * /exploration_node/manager/control_points_distance: 0.35
 * /exploration_node/manager/dynamic_environment: 0
 * /exploration_node/manager/local_segment_length: 6.0
 * /exploration_node/manager/max_acc: 0.8
 * /exploration_node/manager/max_jerk: 4.0
 * /exploration_node/manager/max_vel: 0.8
 * /exploration_node/manager/min_time: True
 * /exploration_node/manager/use_active_perception: True
 * /exploration_node/manager/use_geometric_path: True
 * /exploration_node/manager/use_kinodynamic_path: True
 * /exploration_node/manager/use_optimization: True
 * /exploration_node/manager/use_topo_path: True
 * /exploration_node/map_ros/cx: 320.0
 * /exploration_node/map_ros/cy: 240.0
 * /exploration_node/map_ros/depth_filter_margin: 2
 * /exploration_node/map_ros/depth_filter_maxdist: 11.0
 * /exploration_node/map_ros/depth_filter_mindist: 0.25
 * /exploration_node/map_ros/esdf_slice_height: 0.3
 * /exploration_node/map_ros/frame_id: world
 * /exploration_node/map_ros/fx: 554.2562866210938
 * /exploration_node/map_ros/fy: 554.2562866210938
 * /exploration_node/map_ros/k_depth_scaling_factor: 1000.0
 * /exploration_node/map_ros/show_all_map: True
 * /exploration_node/map_ros/show_esdf_time: False
 * /exploration_node/map_ros/show_occ_time: False
 * /exploration_node/map_ros/skip_pixel: 2
 * /exploration_node/map_ros/visualization_truncate_height: 50.0
 * /exploration_node/map_ros/visualization_truncate_low: -2.0
 * /exploration_node/optimization/algorithm1: 15
 * /exploration_node/optimization/algorithm2: 11
 * /exploration_node/optimization/dist0: 0.8
 * /exploration_node/optimization/ld_dist: 50.0
 * /exploration_node/optimization/ld_end: 100.0
 * /exploration_node/optimization/ld_feasi: 400.0
 * /exploration_node/optimization/ld_guide: 1.5
 * /exploration_node/optimization/ld_smooth: 40.0
 * /exploration_node/optimization/ld_start: 10000.0
 * /exploration_node/optimization/ld_time: 20.0
 * /exploration_node/optimization/ld_view: 0.0
 * /exploration_node/optimization/ld_waypt: 100.0
 * /exploration_node/optimization/max_acc: 0.8
 * /exploration_node/optimization/max_iteration_num1: 2
 * /exploration_node/optimization/max_iteration_num2: 2000
 * /exploration_node/optimization/max_iteration_num3: 200
 * /exploration_node/optimization/max_iteration_num4: 200
 * /exploration_node/optimization/max_iteration_time1: 0.0001
 * /exploration_node/optimization/max_iteration_time2: 0.005
 * /exploration_node/optimization/max_iteration_time3: 0.003
 * /exploration_node/optimization/max_iteration_time4: 0.003
 * /exploration_node/optimization/max_vel: 0.8
 * /exploration_node/perception_utils/left_angle: 0.7
 * /exploration_node/perception_utils/left_angle_pred: 0.72
 * /exploration_node/perception_utils/max_dist: 10.5
 * /exploration_node/perception_utils/right_angle: 0.7
 * /exploration_node/perception_utils/right_angle_pred: 0.72
 * /exploration_node/perception_utils/top_angle: 0.7
 * /exploration_node/perception_utils/top_angle_pred: 0.72
 * /exploration_node/perception_utils/vis_dist: 1.0
 * /exploration_node/predmanager/center_x: 39.0
 * /exploration_node/predmanager/far_goal: 12.0
 * /exploration_node/predmanager/finish_num: 10
 * /exploration_node/predmanager/map_size: 30.0
 * /exploration_node/predmanager/sphere_radius: 4.0
 * /exploration_node/reconfsm/cx: 640.0
 * /exploration_node/reconfsm/cy: 480.0
 * /exploration_node/reconfsm/fx: 762.7222900390625
 * /exploration_node/reconfsm/fy: 762.7222900390625
 * /exploration_node/reconfsm/img_dir_: Your IMG Folder
 * /exploration_node/reconfsm/img_flag: False
 * /exploration_node/reconfsm/noise_mean: 0.0
 * /exploration_node/reconfsm/noise_variance: 0.07
 * /exploration_node/reconfsm/replan_1: 1.5
 * /exploration_node/reconfsm/replan_2: 3.0
 * /exploration_node/reconfsm/replan_proportion: 0.4
 * /exploration_node/reconfsm/replan_time: 0.8
 * /exploration_node/sdf_map/box_max_x: 39.0
 * /exploration_node/sdf_map/box_max_y: 22.0
 * /exploration_node/sdf_map/box_max_z: 22.5
 * /exploration_node/sdf_map/box_min_x: -5.0
 * /exploration_node/sdf_map/box_min_y: -22.0
 * /exploration_node/sdf_map/box_min_z: 0.0
 * /exploration_node/sdf_map/default_dist: 0.0
 * /exploration_node/sdf_map/ground_height: -1.0
 * /exploration_node/sdf_map/local_bound_inflate: 0.5
 * /exploration_node/sdf_map/local_map_margin: 50
 * /exploration_node/sdf_map/map_size_x: 45.0
 * /exploration_node/sdf_map/map_size_y: 45.0
 * /exploration_node/sdf_map/map_size_z: 23.0
 * /exploration_node/sdf_map/max_ray_length: 10.5
 * /exploration_node/sdf_map/min_ray_length: 0.5
 * /exploration_node/sdf_map/obstacles_inflation: 0.199
 * /exploration_node/sdf_map/optimistic: False
 * /exploration_node/sdf_map/p_hit: 0.65
 * /exploration_node/sdf_map/p_max: 0.9
 * /exploration_node/sdf_map/p_min: 0.12
 * /exploration_node/sdf_map/p_miss: 0.35
 * /exploration_node/sdf_map/p_occ: 0.8
 * /exploration_node/sdf_map/prediction_max_ray_length: 30.5
 * /exploration_node/sdf_map/resolution: 0.1
 * /exploration_node/sdf_map/signed_dist: False
 * /exploration_node/sdf_map/view_pos_threshold: 0.5
 * /exploration_node/sdf_map/virtual_ceil_height: -10
 * /exploration_node/search/allocate_num: 100000
 * /exploration_node/search/check_num: 10
 * /exploration_node/search/horizon: 5.0
 * /exploration_node/search/init_max_tau: 1.0
 * /exploration_node/search/lambda_heu: 10.0
 * /exploration_node/search/margin: 0.2
 * /exploration_node/search/max_acc: 0.8
 * /exploration_node/search/max_tau: 0.8
 * /exploration_node/search/max_vel: 0.8
 * /exploration_node/search/optimistic: False
 * /exploration_node/search/resolution_astar: 0.025
 * /exploration_node/search/time_resolution: 0.8
 * /exploration_node/search/vel_margin: 0.25
 * /exploration_node/search/w_time: 10.0
 * /exploration_node/surf_pred/model_: /home/rc/Document...
 * /rosdistro: noetic
 * /rosversion: 1.16.0
 * /traj_server/perception_utils/left_angle: 0.69222
 * /traj_server/perception_utils/max_dist: 6.5
 * /traj_server/perception_utils/right_angle: 0.68901
 * /traj_server/perception_utils/top_angle: 0.56125
 * /traj_server/perception_utils/vis_dist: 1.0
 * /traj_server/traj_server/init_x: 0.0
 * /traj_server/traj_server/init_y: 0.0
 * /traj_server/traj_server/init_z: 1.0
 * /traj_server/traj_server/pub_traj_id: 4
 * /traj_server/traj_server/time_forward: 1.5
 * /waypoint_generator/waypoint_type: point

NODES
  /
    exploration_node (exploration_manager/exploration_node)
    traj_server (plan_manage/traj_server)
    waypoint_generator (waypoint_generator/waypoint_generator)

ROS_MASTER_URI=http://localhost:11311

process[exploration_node-1]: started with pid [40254]
process[traj_server-2]: started with pid [40255]
process[waypoint_generator-3]: started with pid [40256]
hit: 0.619039, miss: -0.619039, min: -1.99243, max: 2.19722, thresh: 1.38629
[ WARN] [1,699,870,497.683,923,126]: [Traj server]: init...
origin_:    -1 -22.5    -1
map size: 45 45 23
hit: 0.619039, miss: -0.619039, min: -1.99243, max: 2.19722, thresh: 1.38629
0
0
origin_:    -1 -22.5    -1
map size: 45 45 23
origin_:    -1 -22.5    -1
map size: 45 45 23
yaw diff: 0.523599
max yaw diff: 0.174533
vert num: 5
top:        0
 0.84659
0.532245
bottom:        0
-0.84659
0.532245
left: 0.769831
       0
0.638248
right: -0.771876
        0
 0.635773
lefttop: -3.73084  -2.3951      4.5
leftbottom: -2.87212   2.3951      4.5
righttop: 2.86098 -2.3951     4.5
rightbottom: 2.86098  2.3951     4.5
T_cb:  0 -1  0  0
 0  0  1  0
 1  0  0  0
 0  0  0  1
T_bc: -0 -0  1  0
-1 -0  0 -0
-0  1 -0  0
 0 -0  0  1
Planner Ready!
CUDA ready!
Model loaded!
Warm-Up Started!
Warm-Up Finished!
hit: 0.619039, miss: -0.619039, min: -1.99243, max: 2.19722, thresh: 1.38629
origin_:    -1 -22.5    -1
map size: 45 45 23
origin_:    -1 -22.5    -1
map size: 45 45 23
yaw diff: 0.523599
max yaw diff: 0.174533
vert num: 5
top:        0
 0.84659
0.532245
bottom:        0
-0.84659
0.532245
left: 0.769831
       0
0.638248
right: -0.771876
        0
 0.635773
lefttop: -3.73084  -2.3951      4.5
leftbottom: -2.87212   2.3951      4.5
righttop: 2.86098 -2.3951     4.5
rightbottom: 2.86098  2.3951     4.5
T_cb:  0 -1  0  0
 0  0  1  0
 1  0  0  0
 0  0  0  1
T_bc: -0 -0  1  0
-1 -0  0 -0
-0  1 -0  0
 0 -0  0  1
origin_:    -1 -22.5    -1
map size: 45 45 23
[ INFO] [1,699,870,505.367,878,205]: [FSM]: state: INITIAL
[ WARN] [1,699,870,505.369,052,778]: no odom.
[FSM]: from INITIAL to WAIT
[ INFO] [1,699,870,506.720,291,243]: [FSM]: state: WAIT
[ WARN] [1,699,870,506.720,329,420]: wait for trigger.
[ INFO] [1,699,870,508.290,778,807]: [FSM]: state: WAIT
[ WARN] [1,699,870,508.290,817,331]: wait for trigger.
[ INFO] [1,699,870,509.882,942,202]: [FSM]: state: WAIT
[ WARN] [1,699,870,509.882,983,269]: wait for trigger.
[ INFO] [1,699,870,511.574,002,498]: [FSM]: state: WAIT
[ WARN] [1,699,870,511.574,032,618]: wait for trigger.
Triggered!
[triggerCallback]: from WAIT to PLAN
[ WARN] [1,699,870,512.497,426,853]: STATIC!
start_pt_x:0
start_pt_y:0
start_pt_z:1.52775
-----Planning Start!-----
-----Surface Prediction Start!-----
infer_ms:1.143ms
ts_ms:5.49819ms
vec_ms:0.011496ms
[ WARN] [1,699,870,512.515,397,998]: near_ground
351
[ WARN] [1,699,870,512.551,062,617]: Visit Cloud!
visit_num:8399
0.203145
Surface_Prediction_Time:53.7338ms!
-----Surface Prediction Finished!-----
-----Global Planning Start!-----
preprocess_time:0.074823ms
-----------cluster_size:64
CEC_time:19.9874ms
visibility_time:0.040793ms
cloud number:23389
update_time:159.248ms
global planner
No:11no normal mech!!!!!!!!!!!!
global planner
No:12no normal mech!!!!!!!!!!!!
global planner
No:14no normal mech!!!!!!!!!!!!
global planner
No:15no normal mech!!!!!!!!!!!!
global planner
No:17no normal mech!!!!!!!!!!!!
global planner
No:18no normal mech!!!!!!!!!!!!
global planner
No:19no normal mech!!!!!!!!!!!!
global planner
No:25no normal mech!!!!!!!!!!!!
global planner
No:26no normal mech!!!!!!!!!!!!
global planner
No:28no normal mech!!!!!!!!!!!!
global planner
No:29no normal mech!!!!!!!!!!!!
global planner
No:30no normal mech!!!!!!!!!!!!
global planner
No:31no normal mech!!!!!!!!!!!!
global planner
No:32no normal mech!!!!!!!!!!!!
global planner
No:39no normal mech!!!!!!!!!!!!
global planner
No:40no normal mech!!!!!!!!!!!!
global planner
No:42no normal mech!!!!!!!!!!!!
global planner
No:43no normal mech!!!!!!!!!!!!
global planner
No:44no normal mech!!!!!!!!!!!!
global planner
No:46no normal mech!!!!!!!!!!!!
global planner
No:55no normal mech!!!!!!!!!!!!
global planner
No:57no normal mech!!!!!!!!!!!!
global planner
No:58no normal mech!!!!!!!!!!!!
global planner
No:63no normal mech!!!!!!!!!!!!
partition_size:66
normal_select_time:1.92143ms
qualified_partition_size:66
sample_time:8.97807ms

TSP_time:42.8108ms
[ WARN] [1,699,870,512.787,840,830]: global nbv yaw!
0.758556deg.
total_global:233.061ms
[ WARN] [1,699,870,512.787,880,946]: Global to NBV!
dist to NBV:5.57936
Global_Planning_Time:236.674ms!
-----Global Planning Finished!-----
-----Local Planning Start!-----
-----Local Planning Finished!-----
Local_Planning_Time:2.70036ms!
initial_local_path_length:5.57936m
initial_stoe:5.57936
[ERROR] [1,699,870,512.800,510,696]: Real Length!
real length:6.14249
start to end:5.57936
duration: 15.3562, seg_num: 17, dt: 0.903308
Iter num: 79, time: 0.000687604, point num: 20, comb time: 8.9958e-05
dt_yaw: 0.637289, start yaw: 7.08578e-07           0           0, end: 0.0132393
nlopt failure
Traj_Opt_Time:11.8007ms!
Planning_Time:304.923ms!
-----Planning Finished!-----
traj_id:1_id!
[FSM]: from PLAN to EXEC
[ WARN] [1,699,870,512.956,465,393]: EXEC traj!
[ INFO] [1,699,870,513.812,111,626]: [FSM]: state: EXEC
collision at: -0.0373385  0.0323704    1.56665
[ WARN] [1,699,870,513.812,301,913]: Replan: collision detected==================================
[safetyCallback]: from EXEC to PLAN
-----Planning Start!-----
-----Surface Prediction Start!-----
infer_ms:1.0916ms
ts_ms:3.796ms
vec_ms:0.008719ms
[ WARN] [1,699,870,514.631,659,801]: near_ground
345
[ WARN] [1,699,870,514.666,746,098]: Visit Cloud!
visit_num:4303
0.203145
Surface_Prediction_Time:41.278ms!
-----Surface Prediction Finished!-----
-----Global Planning Start!-----
preprocess_time:0.063234ms
-----------cluster_size:62
CEC_time:10.2253ms
visibility_time:0.040559ms
cloud number:23383
update_time:154.851ms
global planner
No:11no normal mech!!!!!!!!!!!!
global planner
No:12no normal mech!!!!!!!!!!!!
global planner
No:14no normal mech!!!!!!!!!!!!
global planner
No:15no normal mech!!!!!!!!!!!!
global planner
No:17no normal mech!!!!!!!!!!!!
global planner
No:25no normal mech!!!!!!!!!!!!
global planner
No:26no normal mech!!!!!!!!!!!!
global planner
No:28no normal mech!!!!!!!!!!!!
global planner
No:38no normal mech!!!!!!!!!!!!
global planner
No:39no normal mech!!!!!!!!!!!!
global planner
No:41no normal mech!!!!!!!!!!!!
global planner
No:53no normal mech!!!!!!!!!!!!
global planner
No:55no normal mech!!!!!!!!!!!!
global planner
No:56no normal mech!!!!!!!!!!!!
global planner
No:61no normal mech!!!!!!!!!!!!
partition_size:64
normal_select_time:1.11635ms
qualified_partition_size:64
sample_time:7.99356ms

TSP_time:70.5308ms
[ WARN] [1,699,870,514.914,982,426]: global nbv yaw!
-59.6549deg.
total_global:244.821ms
[ WARN] [1,699,870,514.915,016,396]: Global to NBV!
dist to NBV:4.67293
Global_Planning_Time:248.181ms!
-----Global Planning Finished!-----
-----Local Planning Start!-----
-----Local Planning Finished!-----
Local_Planning_Time:0.136157ms!
initial_local_path_length:4.67293m
initial_stoe:4.67293
[ERROR] [1,699,870,514.921,727,045]: Real Length!
real length:5.04882
start to end:4.67293
duration: 12.622, seg_num: 15, dt: 0.84147
Iter num: 233, time: 0.00502997, point num: 18, comb time: 0.000151094
dt_yaw: 0.521753, start yaw: 0 0 0, end: -1.04117
Traj_Opt_Time:12.1513ms!
Planning_Time:301.76ms!
-----Planning Finished!-----
traj_id:2_id!
[FSM]: from PLAN to EXEC
[ WARN] [1,699,870,515.71,171,436]: EXEC traj!
[ INFO] [1,699,870,516.7,728,972]: [FSM]: state: EXEC
[ WARN] [1,699,870,517.868,652,065]: [Traj server]: ready.
[ INFO] [1,699,870,518.20,898,593]: [FSM]: state: EXEC
[FSM]: from EXEC to PLAN
[ WARN] [1,699,870,518.20,933,941]: Replan: periodic call=======================================
[ INFO] [1,699,870,519.26,017,778]: [FSM]: state: PLAN
-----Planning Start!-----
-----Surface Prediction Start!-----
infer_ms:1.05696ms
ts_ms:5.49376ms
vec_ms:0.008646ms
[ WARN] [1,699,870,519.33,759,829]: near_ground
344
[ WARN] [1,699,870,519.33,890,834]: Prediction Diff
0
[ WARN] [1,699,870,519.67,900,396]: Visit Cloud!
visit_num:4304

Px4 ctrl queries

Hi, Hope you are doing well.
thanks for great work!
I have been using px4 ctrl("https://github.com/ZJU-FAST-Lab/Fast-Drone-250/tree/master/src/realflight_modules/px4ctrl") and things are working fine but i was going through your repo and found out ("https://github.com/HKUST-Aerial-Robotics/PredRecon/tree/master/Planner/Code/src/px4ctrl") and i started comparing it i found there huge change in this and an additional file "https://github.com/HKUST-Aerial-Robotics/PredRecon/blob/master/Planner/Code/src/px4ctrl/src/hovthrkf.cpp", so what are changes from the previous one and i am planning to use it in real world so do i need to change anything apart from topic or is it just for simulation.

Thankyou

May I download the repository by using the "Download ZIP" button directly?

Thanks for your brilliant work! However, when I used the code below,
git clone [email protected]:HKUST-Aerial-Robotics/PredRecon.git
it showed the error

Cloning into 'PredRecon'...
[email protected]: Permission denied (publickey).
fatal: Could not read from remote repository.

Please make sure you have the correct access rights
and the repository exists.

May I download the repository by using the "Download ZIP" button directly?

Request for rqt_graph in reconstruction simulation

The planner cannot work properly and the drone seems cannot collect images. The screenshots are given below.

Screenshot from 2024-01-25 15-30-28
Screenshot from 2024-01-25 15-30-18

I have checked the code and rqt graph. It is abnormal that the recon.launch file launches three ros nodes: 'waypoint_generator', 'traj_server', and 'exploration_node', while in my rqt_graph, I could only find the 'waypoint_generator' is active. I would like to request your rqt_graph while reconstruction to debug the topics and node states.

Screenshot from 2024-01-25 17-35-50

I am looking forward to your reply.

The output of the recon.launch file is also given below.

ROS_MASTER_URI=http://localhost:11311

process[exploration_node-1]: started with pid [1342618]
process[traj_server-2]: started with pid [1342619]
process[waypoint_generator-3]: started with pid [1342620]
[ WARN] [1,706,167,787.444,030,751]: [Traj server]: init...
hit: 0.619039, miss: -0.619039, min: -1.99243, max: 2.19722, thresh: 1.38629
0
0
origin_:    -1 -22.5    -1
map size: 45 45 23
hit: 0.619039, miss: -0.619039, min: -1.99243, max: 2.19722, thresh: 1.38629
origin_:    -1 -22.5    -1
map size: 45 45 23
origin_:    -1 -22.5    -1
map size: 45 45 23
yaw diff: 0.523599
max yaw diff: 0.174533
vert num: 5
top:        0
 0.84659
0.532245
bottom:        0
-0.84659
0.532245
left: 0.769831
       0
0.638248
right: -0.771876
        0
 0.635773
lefttop: -3.73084  -2.3951      4.5
leftbottom: -2.87212   2.3951      4.5
righttop: 2.86098 -2.3951     4.5
rightbottom: 2.86098  2.3951     4.5
T_cb:  0 -1  0  0
 0  0  1  0
 1  0  0  0
 0  0  0  1
T_bc: -0 -0  1  0
-1 -0  0 -0
-0  1 -0  0
 0 -0  0  1
Planner Ready!
CUDA ready!
Model loaded!
Warm-Up Started!
Warm-Up Finished!
hit: 0.619039, miss: -0.619039, min: -1.99243, max: 2.19722, thresh: 1.38629
origin_:    -1 -22.5    -1
map size: 45 45 23
origin_:    -1 -22.5    -1
map size: 45 45 23
yaw diff: 0.523599
max yaw diff: 0.174533
vert num: 5
top:        0
 0.84659
0.532245
bottom:        0
-0.84659
0.532245
left: 0.769831
       0
0.638248
right: -0.771876
        0
 0.635773
lefttop: -3.73084  -2.3951      4.5
leftbottom: -2.87212   2.3951      4.5
righttop: 2.86098 -2.3951     4.5
rightbottom: 2.86098  2.3951     4.5
T_cb:  0 -1  0  0
 0  0  1  0
 1  0  0  0
 0  0  0  1
T_bc: -0 -0  1  0
-1 -0  0 -0
-0  1 -0  0
 0 -0  0  1
origin_:    -1 -22.5    -1
map size: 45 45 23
[ INFO] [1,706,167,801.119,477,295]: [FSM]: state: INITIAL
[ WARN] [1,706,167,801.120,682,832]: no odom.
[ INFO] [1,706,167,802.406,008,194]: [FSM]: state: INITIAL
[FSM]: from INITIAL to WAIT
[ INFO] [1,706,167,803.911,381,674]: [FSM]: state: WAIT
[ WARN] [1,706,167,803.911,563,226]: wait for trigger.
[ INFO] [1,706,167,805.104,356,689]: [FSM]: state: WAIT
[ WARN] [1,706,167,805.104,549,715]: wait for trigger.
[ INFO] [1,706,167,806.496,053,764]: [FSM]: state: WAIT
[ WARN] [1,706,167,806.496,101,466]: wait for trigger.
Triggered!
[triggerCallback]: from WAIT to PLAN
[ INFO] [1,706,167,807.534,851,277]: [FSM]: state: PLAN
[ WARN] [1,706,167,807.535,202,674]: STATIC!
start_pt_x:0
start_pt_y:0
start_pt_z:1.53138
-----Planning Start!-----
-----Surface Prediction Start!-----
infer_ms:1.49482ms
ts_ms:5.78514ms
vec_ms:0.016234ms
[ WARN] [1,706,167,807.544,806,947]: near_ground
927
[ WARN] [1,706,167,807.693,939,832]: [Traj server]: ready.
[ WARN] [1,706,167,807.716,315,244]: Visit Cloud!
visit_num:6988
0.200179
Surface_Prediction_Time:180.919ms!
-----Surface Prediction Finished!-----
-----Global Planning Start!-----
preprocess_time:0.100306ms
-----------cluster_size:18
CEC_time:20.7482ms
visibility_time:0.038641ms
cloud number:22985
update_time:336.026ms
partition_size:19
normal_select_time:2.12947ms
qualified_partition_size:19
sample_time:14.8858ms

TSP_time:12.2654ms
[ WARN] [1,706,167,808.105,971,600]: global nbv yaw!
2.53668deg.
total_global:386.194ms
[ WARN] [1,706,167,808.106,220,947]: Global to NBV!
dist to NBV:6.9341
Global_Planning_Time:389.903ms!
-----Global Planning Finished!-----
-----Local Planning Start!-----
None qualified viewpoints...
i:1

None qualified viewpoints...
---Construct Graph---
---Search optimal sequence---
Node: 4, edge: 3
[ WARN] [1,706,167,808.110,349,099]: Same pos!
---Search Finish---
---Push Finish---
-----Local Planning Finished!-----
Local_Planning_Time:4.12948ms!
initial_local_path_length:7.03166m
initial_stoe:6.9341
[ERROR] [1,706,167,808.165,029,674]: Real Length!
real length:7.62633
start to end:6.9341
duration: 19.0658, seg_num: 24, dt: 0.794409
Iter num: 81, time: 0.00513926, point num: 27, comb time: 0.000289158
dt_yaw: 0.791822, start yaw: 7.08578e-07           0           0, end: 0.0442733
Traj_Opt_Time:60.7009ms!
Planning_Time:637.65ms!
-----Planning Finished!-----
traj_id:1_id!
[FSM]: from PLAN to EXEC
[ WARN] [1,706,167,808.526,575,489]: EXEC traj!
[ INFO] [1,706,167,810.230,825,526]: [FSM]: state: EXEC
[ INFO] [1,706,167,811.834,464,011]: [FSM]: state: EXEC
[FSM]: from EXEC to PLAN
[ WARN] [1,706,167,811.834,711,704]: Replan: periodic call=======================================
[ INFO] [1,706,167,813.378,635,441]: [FSM]: state: PLAN
-----Planning Start!-----
-----Surface Prediction Start!-----
infer_ms:1.56825ms
ts_ms:9.03769ms
vec_ms:0.010923ms
[ WARN] [1,706,167,813.392,073,819]: near_ground
918
[ WARN] [1,706,167,813.515,959,218]: Visit Cloud!
visit_num:3631
0.200179
Surface_Prediction_Time:137.763ms!
-----Surface Prediction Finished!-----
-----Global Planning Start!-----
preprocess_time:0.153066ms
-----------cluster_size:18
CEC_time:7.50655ms
visibility_time:0.067381ms
cloud number:22976
update_time:244.347ms
No:16no normal mech!!!!!!!!!!!!
partition_size:18
normal_select_time:7.56886ms
qualified_partition_size:18
sample_time:45.5496ms

TSP_time:16.3766ms
[ WARN] [1,706,167,813.848,144,019]: global nbv yaw!
-58.478deg.
total_global:321.569ms
[ WARN] [1,706,167,813.848,248,959]: Global to NBV!
dist to NBV:11.9875
Global_Planning_Time:331.558ms!
-----Global Planning Finished!-----
-----Local Planning Start!-----
None qualified viewpoints...
i:1

None qualified viewpoints...
---Construct Graph---
---Search optimal sequence---
Node: 4, edge: 3
[ WARN] [1,706,167,813.850,703,933]: Same pos!
---Search Finish---
---Push Finish---
-----Local Planning Finished!-----
Local_Planning_Time:2.47844ms!
[ WARN] [1,706,167,813.850,830,468]: Far Goal!
initial_local_path_length:12.6697m
initial_stoe:11.9875
[ERROR] [1,706,167,813.960,032,009]: Real Length!
real length:13.9204
start to end:11.9875
duration: 34.8011, seg_num: 41, dt: 0.848808
Iter num: 37, time: 0.00133095, point num: 44, comb time: 0.0003582
dt_yaw: 1.82711, start yaw:   0.0163976  0.00511843 0.000783172, end: -1.02063
Traj_Opt_Time:115.239ms!
Planning_Time:587.354ms!
-----Planning Finished!-----
traj_id:2_id!
[FSM]: from PLAN to EXEC
[ WARN] [1,706,167,814.305,285,448]: EXEC traj!
[ INFO] [1,706,167,816.28,990,503]: [FSM]: state: EXEC
[ INFO] [1,706,167,817.286,044,465]: [FSM]: state: EXEC
[ INFO] [1,706,167,818.368,485,870]: [FSM]: state: EXEC
[FSM]: from EXEC to PLAN
[ WARN] [1,706,167,818.368,788,995]: Replan: periodic call=======================================
[ INFO] [1,706,167,819.917,880,637]: [FSM]: state: PLAN
-----Planning Start!-----
-----Surface Prediction Start!-----
infer_ms:1.5188ms
ts_ms:6.6689ms
vec_ms:0.012297ms
[ WARN] [1,706,167,819.927,994,301]: near_ground
918
[ WARN] [1,706,167,819.928,316,318]: Prediction Diff
0
[ WARN] [1,706,167,820.24,147,786]: Visit Cloud!
visit_num:3629
0.200179
Surface_Prediction_Time:106.403ms!
-----Surface Prediction Finished!-----
-----Global Planning Start!-----
preprocess_time:0.126654ms
-----------cluster_size:18
CEC_time:3.45084ms
visibility_time:0.120922ms
cloud number:22976
update_time:153.819ms
No:16no normal mech!!!!!!!!!!!!
partition_size:18
normal_select_time:0.81608ms
qualified_partition_size:18
sample_time:13.4497ms

Originally posted by @JohannaXie in #7 (comment)

About Data

In your SPM/data/Read.me
"Please download PCN.zip or CAD dataset from Cloud and unzip it here."
I don't find PCN.zip or where i can download it.

and i also try to use SPM/dataset/generation to generate data, but i find it couldn't generate data by your code, can you help me.
thx

ply file to pcd file in PCN.zip

I have downloaded the PCN.zip and unzip it in the file folder of "data",should I convert all the ply files in PCN.zip to pcd files? If so, I wonder to know if there's a convenient way to convert all the files at once.
Thanks!

catkin_make error

In November last year, I could compile the program but rviz had no interface. Now I re-git the source code, but this time the compilation fail. I try to add the library of the active_perception to the cmakelists in the plan_env,yet it still occurrs error.

/PredRecon/Planner/Code/src/predrecon/plan_env/src/map_ros.cpp:2:10: fatal error: active_perception/perception_utils.h: No such file or directory
2 | #include <active_perception/perception_utils.h>
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated.

So am I the only one getting this error?

An error occurred while running recon.launch

Thank you for open-source such outstanding work. I encountered the following error while replicating the Planner module, any advice is useful.

I used UE4.25 with Airsim, CUDA11.7, and other LiBs provided in readme. However, the following error occurs.

  1. The following error message occurs when I open UE with se3plan.uproject, but I don't know how to solve it.

Screenshot from 2023-10-30 10-47-53

  1. After running recon.launch in the terminal, use the 2D Nav trigger in Rviz to specify a point, and the terminal displays the following error. What is the reason for this?
lefttop: -3.73084  -2.3951      4.5
leftbottom: -2.87212   2.3951      4.5
righttop: 2.86098 -2.3951     4.5
rightbottom: 2.86098  2.3951     4.5
T_cb:  0 -1  0  0
 0  0  1  0
 1  0  0  0
 0  0  0  1
T_bc: -0 -0  1  0
-1 -0  0 -0
-0  1 -0  0
 0 -0  0  1
origin_:    -1 -22.5    -1
map size: 45 45 23
[ INFO] [1,698,631,932.852,163,587]: [FSM]: state: INITIAL
[FSM]: from INITIAL to WAIT
[ WARN] [1,698,631,933.525,175,465]: wait for trigger.
[ INFO] [1,698,631,934.247,925,808]: [FSM]: state: WAIT
[ WARN] [1,698,631,935.69,684,683]: wait for trigger.
[ INFO] [1,698,631,935.984,829,927]: [FSM]: state: WAIT
[ WARN] [1,698,631,936.930,577,487]: wait for trigger.
[ INFO] [1,698,631,937.848,227,305]: [FSM]: state: WAIT
[ WARN] [1,698,631,938.802,711,156]: wait for trigger.
[ INFO] [1,698,631,939.690,280,084]: [FSM]: state: WAIT
[ WARN] [1,698,631,940.633,264,040]: wait for trigger.
[ INFO] [1,698,631,941.465,522,071]: [FSM]: state: WAIT
[ WARN] [1,698,631,942.351,742,612]: wait for trigger.
[ INFO] [1,698,631,943.289,493,764]: [FSM]: state: WAIT
[ WARN] [1,698,631,944.248,082,794]: wait for trigger.
[ INFO] [1,698,631,945.289,668,668]: [FSM]: state: WAIT
[ WARN] [1,698,631,945.289,708,432]: wait for trigger.
Triggered!
[triggerCallback]: from WAIT to PLAN
[ WARN] [1,698,631,945.346,573,251]: [Traj server]: ready.
[ WARN] [1,698,631,946.255,639,930]: STATIC!
start_pt_x:0
start_pt_y:0
start_pt_z:1.52774
-----Planning Start!-----
-----Surface Prediction Start!-----
infer_ms:1.17383ms
ts_ms:3.74282ms
vec_ms:0.014298ms
[ WARN] [1,698,631,946.263,879,686]: near_ground
416
[ WARN] [1,698,631,946.296,217,317]: Visit Cloud!
visit_num:8635
0.313125
Surface_Prediction_Time:40.6787ms!
-----Surface Prediction Finished!-----
-----Global Planning Start!-----
preprocess_time:0.105435ms
-----------cluster_size:66
CEC_time:19.0792ms
visibility_time:0.040305ms
cloud number:24216
update_time:160.389ms
No:2no normal mech!!!!!!!!!!!!
No:12no normal mech!!!!!!!!!!!!
No:13no normal mech!!!!!!!!!!!!
No:15no normal mech!!!!!!!!!!!!
No:16no normal mech!!!!!!!!!!!!
No:18no normal mech!!!!!!!!!!!!
No:26no normal mech!!!!!!!!!!!!
No:27no normal mech!!!!!!!!!!!!
No:29no normal mech!!!!!!!!!!!!
No:30no normal mech!!!!!!!!!!!!
No:31no normal mech!!!!!!!!!!!!
No:32no normal mech!!!!!!!!!!!!
No:33no normal mech!!!!!!!!!!!!
No:41no normal mech!!!!!!!!!!!!
No:42no normal mech!!!!!!!!!!!!
No:44no normal mech!!!!!!!!!!!!
No:45no normal mech!!!!!!!!!!!!
No:46no normal mech!!!!!!!!!!!!
No:47no normal mech!!!!!!!!!!!!
No:48no normal mech!!!!!!!!!!!!
No:58no normal mech!!!!!!!!!!!!
No:60no normal mech!!!!!!!!!!!!
No:61no normal mech!!!!!!!!!!!!
partition_size:68
normal_select_time:1.88258ms
qualified_partition_size:68
sample_time:10.6405ms

*** Error ***
Cannot open PARAMETER_FILE: "tsp_dir/single.par"
[exploration_node-1] process has died [pid 10944, exit code 1, cmd /home/rc/Projects/devel/lib/exploration_manager/exploration_node /odom_world:=/airsim_node/drone_1/odom_local_enu /map_ros/pose:=/airsim_node/drone_1/odom_local_enu /map_ros/depth:=/airsim_node/drone_1/front_center/DepthPerspective /map_ros/cloud:=/cloud __name:=exploration_node __log:=/home/rc/.ros/log/3d8e8498-76c9-11ee-9644-9980a9a90628/exploration_node-1.log].
log file: /home/rc/.ros/log/3d8e8498-76c9-11ee-9644-9980a9a90628/exploration_node-1*.log
^C[waypoint_generator-3] killing on exit
[traj_server-2] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete
done

Is it possible to use spm model instead of spm_distill model to convert to .pt file?

Hi, is it possible to use spm model instead of spm_distill model to convert to .pt file? When we load the spm model using the code 'lib_predictor.py', the line 'torch.jit.trace' gives error says:

Could not export Python function call '_Voxelization'. Remove calls to Python functions before export. Did you forget to add @script or @script_method annotation? If this is a nn.ModuleList, add it to __constants__:

Do you guys have any suggestions on solving this problem? Thank you.

rpclib: client error C0002: Function 'simGetImages' was called with an invalid number of arguments. Expected: 2, got: 3

I successfully compiled the planner, but when I executed the "source devel/setup.zsh && roslaunch airsim_ros_pkgs airsim_node.launch" step, it prompted "rpclib: client error C0002: Function 'simGetImages' was called with an invalid number of arguments. Expected: 2, got: 3". I checked and found that this is generally because the AiSim client and server need to use the same version, and my airsim is version 1.8.1, so how could I solve the problem?
image

Request the dataset you are using

I wonder if you can provide the processed data set. When I use the PCN data set, there are multiple ply files with the same name, such as xxx_1.ply, xxx_2.ply, xxx_3.ply. If they are directly converted into pcd files, the SPM module still cannot read them. I also encountered many unsolvable difficulties when using House3K to generate data sets. So I wanted to ask you if you could provide us with the dataset you used

Could you please provide a trained SPM model to use the planner? And how should I use that spm.pt? There is no explanation in the README, and I tried running the planner and the following problem occurred.

image
image

1.at line 278 in /tmp/binarydeb/ros-noetic-tf2-0.7.7/src/buffer_core.cpp
Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame front_center_optical (parent drone_1) at time 1701680381.192299 according to authority unknown_publisher

2.[ WARN] [1701680381.392415034]: TF_REPEATED_DATA ignoring data with redundant timestamp for frame front_center_optical (parent drone_1) at time 1701680381.391582 according to authority unknown_publisher

3.[exploration_node-1] process has died [pid 505812, exit code -6, cmd /home/willis/AirSim-1.5.0-linux/ros/src/PredRecon/Planner/Code/devel/lib/exploration_manager/exploration_node /odom_world:=/airsim_node/drone_1/odom_local_enu /map_ros/pose:=/airsim_node/drone_1/odom_local_enu /map_ros/depth:=/airsim_node/drone_1/front_center/DepthPerspective /map_ros/cloud:=/cloud __name:=exploration_node __log:=/home/willis/.ros/log/f9a90822-9282-11ee-9a07-cd3be9faaba6/exploration_node-1.log].
log file: /home/willis/.ros/log/f9a90822-9282-11ee-9a07-cd3be9faaba6/exploration_node-1*.log
[ WARN] [1,701,680,290.862,701,204]: [Traj server]: ready.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.