Skip to content

Commit

Permalink
further cleaning the code
Browse files Browse the repository at this point in the history
  • Loading branch information
hridaybavle committed May 7, 2021
1 parent 1b6123f commit f7c0692
Show file tree
Hide file tree
Showing 10 changed files with 3 additions and 254 deletions.
11 changes: 0 additions & 11 deletions include/ps_graph_slam/semantic_graph_slam.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,6 @@
// segmented pointcloud acc to detection
#include "planar_segmentation/point_cloud_segmentation.h"

// semantic mapping
#include "ps_graph_slam/map_cloud.h"
#include "ps_graph_slam/mapping.h"

class semantic_graph_slam {
public:
semantic_graph_slam();
Expand All @@ -37,13 +33,6 @@ class semantic_graph_slam {
private:
std::unique_ptr<point_cloud_segmentation> pc_seg_obj_;
std::unique_ptr<data_association> data_ass_obj_;
// mapping* semantic_mapping_obj_;
// std::thread* semantic_mapping_th_;
// std::thread* semantic_mapping_opt_th_;

public:
// mapping related params
std::vector<map_cloud> get3DMap();

private:
bool empty_keyframe_queue();
Expand Down
2 changes: 0 additions & 2 deletions include/semantic_graph_slam_ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,8 +64,6 @@

#include "ps_graph_slam/semantic_graph_slam.h"

#include "ps_graph_slam/map_cloud.h"

class semantic_graph_slam_ros {

public:
Expand Down
19 changes: 0 additions & 19 deletions launch/octomap.launch

This file was deleted.

44 changes: 0 additions & 44 deletions launch/ps_slam_with_snap_pose_bucket_det_drone_data.launch

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<launch>

<param name="use_sim_time" value="true" />
<!--<arg name="bagfile" default="/media/hriday/0F2F8B1E48317A85/home/Documents/PhD/Rosbags/Semantic_SLAM/semantic_slam/ACL/lab/with_snap_pose/entire_lab/entire_lab_3_rounds.bag"/>-->
<arg name="bagfile" default="/media/hriday/0F2F8B1E48317A85/home/Documents/PhD/Rosbags/Semantic_SLAM/semantic_slam/ACL/lab/with_snap_pose/entire_lab/entire_lab_3_rounds.bag"/>

<!-- Play the bagfile -->
<node pkg="rosbag" type="play" name="rosbag" args="--clock $(arg bagfile)" />
Expand All @@ -26,7 +26,7 @@
<remap from="depth_registered/image_rect" to="/camera/aligned_depth_to_color/image_rect"/>
</node>

<!--shape color object detector -->
<!--shape color object detector
<arg name="front_camera_image_topic_name" default="/camera/color/image_raw" />
<arg name="object_recognized_front_camera_topic_name" default="/image_processed/object_recognized_front_camera" />
<arg name="config_file" default="$(find ShapeColor_ObjectDetection)/cfg/objectDetector_configFile.xml"/>
Expand All @@ -35,7 +35,7 @@
<param name="front_camera_image_topic_name" value="$(arg front_camera_image_topic_name)" type="string"/>
<param name="object_recognized_front_camera_topic_name" value="$(arg object_recognized_front_camera_topic_name)" type="string"/>
<param name="config_file" value="$(arg config_file)" type="string"/>
</node>
</node>-->

<!--launching the semantic slam node -->
<node name="semantic_graph_slam_node" pkg="semantic_SLAM" type="semantic_graph_SLAM_node" output="screen">
Expand Down
42 changes: 0 additions & 42 deletions launch/ps_slam_with_yolo_TUM.launch

This file was deleted.

42 changes: 0 additions & 42 deletions launch/ps_slam_with_yolo_TUM_f1_desk2.launch

This file was deleted.

42 changes: 0 additions & 42 deletions launch/ps_slam_with_yolo_TUM_f2.launch

This file was deleted.

42 changes: 0 additions & 42 deletions launch/ps_slam_with_yolo_TUM_f2_desk.launch

This file was deleted.

7 changes: 0 additions & 7 deletions src/ps_graph_slam/semantic_graph_slam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -389,13 +389,6 @@ void semantic_graph_slam::getDetectedObjectsPose(
seg_obj_vec = seg_obj_vec_;
}

std::vector<map_cloud> semantic_graph_slam::get3DMap() {
std::vector<map_cloud> cloud_map_vector;
// cloud_map_vector = semantic_mapping_obj_->getOutputMap();

return cloud_map_vector;
}

void semantic_graph_slam::saveGraph(std::string save_graph_path) {
graph_slam_->save(save_graph_path);
std::cout << "saved the graph at " << save_graph_path << std::endl;
Expand Down

0 comments on commit f7c0692

Please sign in to comment.