diff --git a/cfg/bucket_detector_workspace_jackal.yaml b/cfg/bucket_detector_workspace_jackal.yaml deleted file mode 100644 index fac56d7..0000000 --- a/cfg/bucket_detector_workspace_jackal.yaml +++ /dev/null @@ -1,26 +0,0 @@ -#general params -verbose: false -camera_angle: -15.0 -update_key_using_det: true -add_first_lan: false -#keyframe -keyframe_delta_trans: 0.5 -keyframe_delta_angle: 0.5 -keyframe_delta_time: 1.0 -#plane segmentation -num_point_seg: 50 -norm_point_thres: 1000 -#data association related -maha_dist_thres: 1.5 -use_maha_dist: false -use_eq_dist: true -eq_dist_thres: 1.5 -land_noise_low: 0.1 -land_noise_high: 0.1 -#odom information cal -use_const_inf_matrix: true -const_stddev_x: 0.0667 -const_stddev_q: 0.001 -#graph slam related -save_graph: false -save_graph_path: /home/hriday/Desktop/semantic_graph.g2o diff --git a/cfg/yolo_detector_rgbd_tum.yaml b/cfg/yolo_detector_rgbd_tum.yaml deleted file mode 100644 index 2f71579..0000000 --- a/cfg/yolo_detector_rgbd_tum.yaml +++ /dev/null @@ -1,31 +0,0 @@ -#general params -verbose: false -camera_angle: 0.0 -update_key_using_det: false -add_first_lan: false -using_kitti: false -use_rovio_odom: false -use_rtab_map_odom: true -#keyframe -keyframe_delta_trans: 0.2 -keyframe_delta_angle: 0.2 -keyframe_delta_time: 0.5 -#plane segmentation -num_point_seg: 100 -norm_point_thres: 2000 -planar_area: 0.15 -#data association related -maha_dist_thres: 0.115 -use_maha_dist: true -use_eq_dist: false -eq_dist_thres: 0.5 -land_noise_low: 0.6 -land_noise_high: 0.6 -#odom information cal -use_const_inf_matrix: true -const_stddev_x: 0.00667 -const_stddev_q: 0.0001 -#graph slam related -save_graph: false -save_graph_path: /home/hriday/Desktop/semantic_graph.g2o -compute_txt_for_ate: true diff --git a/cfg/yolo_detector_rgbd_tum_f1_desk2.yaml b/cfg/yolo_detector_rgbd_tum_f1_desk2.yaml deleted file mode 100644 index 4acdfc3..0000000 --- a/cfg/yolo_detector_rgbd_tum_f1_desk2.yaml +++ /dev/null @@ -1,30 +0,0 @@ -#general params -verbose: true -camera_angle: 0.0 -update_key_using_det: false -add_first_lan: false -using_kitti: false -use_rovio_odom: false -use_rtab_map_odom: true -#keyframe -keyframe_delta_trans: 0.5 -keyframe_delta_angle: 0.5 -keyframe_delta_time: 0.5 -#plane segmentation -num_point_seg: 500 -norm_point_thres: 5000 -#data association related -maha_dist_thres: 0.115 -use_maha_dist: true -use_eq_dist: false -eq_dist_thres: 0.8 -land_noise_low: 0.9 -land_noise_high: 0.9 -#odom information cal -use_const_inf_matrix: true -const_stddev_x: 0.000667 -const_stddev_q: 0.00001 -#graph slam related -save_graph: false -save_graph_path: /home/hriday/Desktop/semantic_graph.g2o -compute_txt_for_ate: true diff --git a/cfg/yolo_detector_rgbd_tum_f2.yaml b/cfg/yolo_detector_rgbd_tum_f2.yaml deleted file mode 100644 index 4acdfc3..0000000 --- a/cfg/yolo_detector_rgbd_tum_f2.yaml +++ /dev/null @@ -1,30 +0,0 @@ -#general params -verbose: true -camera_angle: 0.0 -update_key_using_det: false -add_first_lan: false -using_kitti: false -use_rovio_odom: false -use_rtab_map_odom: true -#keyframe -keyframe_delta_trans: 0.5 -keyframe_delta_angle: 0.5 -keyframe_delta_time: 0.5 -#plane segmentation -num_point_seg: 500 -norm_point_thres: 5000 -#data association related -maha_dist_thres: 0.115 -use_maha_dist: true -use_eq_dist: false -eq_dist_thres: 0.8 -land_noise_low: 0.9 -land_noise_high: 0.9 -#odom information cal -use_const_inf_matrix: true -const_stddev_x: 0.000667 -const_stddev_q: 0.00001 -#graph slam related -save_graph: false -save_graph_path: /home/hriday/Desktop/semantic_graph.g2o -compute_txt_for_ate: true diff --git a/cfg/yolo_detector_rgbd_tum_f2_desk.yaml b/cfg/yolo_detector_rgbd_tum_f2_desk.yaml deleted file mode 100644 index 846ed0f..0000000 --- a/cfg/yolo_detector_rgbd_tum_f2_desk.yaml +++ /dev/null @@ -1,31 +0,0 @@ -#general params -verbose: false -camera_angle: 0.0 -update_key_using_det: false -add_first_lan: false -using_kitti: false -use_rovio_odom: false -use_rtab_map_odom: true -#keyframe -keyframe_delta_trans: 0.1 -keyframe_delta_angle: 0.1 -keyframe_delta_time: 0.5 -#plane segmentation -num_point_seg: 100 -norm_point_thres: 5000 -planar_area: 0.20 -#data association related -maha_dist_thres: 0.35 -use_maha_dist: true -use_eq_dist: false -eq_dist_thres: 0.8 -land_noise_low: 0.3 -land_noise_high: 0.3 -#odom information cal -use_const_inf_matrix: true -const_stddev_x: 0.00667 -const_stddev_q: 0.0001 -#graph slam related -save_graph: false -save_graph_path: /home/hriday/Desktop/semantic_graph.g2o -compute_txt_for_ate: true diff --git a/cfg/bucket_detector.yaml b/config/bucket_detector.yaml similarity index 100% rename from cfg/bucket_detector.yaml rename to config/bucket_detector.yaml diff --git a/cfg/bucket_detector_workspace.yaml b/config/bucket_detector_workspace.yaml similarity index 100% rename from cfg/bucket_detector_workspace.yaml rename to config/bucket_detector_workspace.yaml diff --git a/cfg/yolo_detector.yaml b/config/yolo_detector.yaml similarity index 100% rename from cfg/yolo_detector.yaml rename to config/yolo_detector.yaml diff --git a/cfg/yolo_detector_kitti.yaml b/config/yolo_detector_kitti.yaml similarity index 100% rename from cfg/yolo_detector_kitti.yaml rename to config/yolo_detector_kitti.yaml diff --git a/cfg/yolo_detector_rotonda.yaml b/config/yolo_detector_rotonda.yaml similarity index 100% rename from cfg/yolo_detector_rotonda.yaml rename to config/yolo_detector_rotonda.yaml diff --git a/launch/ps_slam_with_rovio_pose_yolo.launch b/launch/ps_slam_with_rovio_pose_yolo.launch index cee9420..668f341 100755 --- a/launch/ps_slam_with_rovio_pose_yolo.launch +++ b/launch/ps_slam_with_rovio_pose_yolo.launch @@ -35,7 +35,7 @@ - + diff --git a/launch/ps_slam_with_rovio_pose_yolo_corridor.launch b/launch/ps_slam_with_rovio_pose_yolo_corridor.launch index d0295a6..5450c3d 100755 --- a/launch/ps_slam_with_rovio_pose_yolo_corridor.launch +++ b/launch/ps_slam_with_rovio_pose_yolo_corridor.launch @@ -35,7 +35,7 @@ - + diff --git a/launch/ps_slam_with_snap_pose_bucket_det_lab_data.launch b/launch/ps_slam_with_snap_pose_bucket_det_lab_data.launch index e79208d..e7dbb02 100755 --- a/launch/ps_slam_with_snap_pose_bucket_det_lab_data.launch +++ b/launch/ps_slam_with_snap_pose_bucket_det_lab_data.launch @@ -38,7 +38,7 @@ - + diff --git a/launch/ps_slam_with_snap_pose_bucket_det_lab_data_with_octomap.launch b/launch/ps_slam_with_snap_pose_bucket_det_lab_data_with_octomap.launch index ccd171b..c235a5c 100755 --- a/launch/ps_slam_with_snap_pose_bucket_det_lab_data_with_octomap.launch +++ b/launch/ps_slam_with_snap_pose_bucket_det_lab_data_with_octomap.launch @@ -26,7 +26,7 @@ - @@ -35,11 +35,11 @@ - --> + - +