diff --git a/include/gpd/layer.h b/include/gpd/layer.h deleted file mode 100644 index 9daca5a..0000000 --- a/include/gpd/layer.h +++ /dev/null @@ -1,22 +0,0 @@ -#ifndef LAYER_H_ -#define LAYER_H_ - - -class Layer -{ - public: - - virtual ~Layer() { }; - - virtual void forward(); - - - private: - - std::vector weights_; - std::vector inputs_; - std::vector outputs_; -}; - - -#endif /* LAYER_H_ */ diff --git a/include/gpd/net.h b/include/gpd/net.h deleted file mode 100644 index eb6d1ae..0000000 --- a/include/gpd/net.h +++ /dev/null @@ -1,13 +0,0 @@ -#ifndef NET_H_ -#define NET_H_ - - -class Net -{ - private: - - std::vector layers_; -}; - - -#endif /* NET_H */ diff --git a/launch/classify_candidates_file_15_channels.launch b/launch/classify_candidates_file_15_channels.launch index 96359e3..fb54b63 100644 --- a/launch/classify_candidates_file_15_channels.launch +++ b/launch/classify_candidates_file_15_channels.launch @@ -41,7 +41,7 @@ [0, 0, 0] - + diff --git a/src/gpd/grasp_detector.cpp b/src/gpd/grasp_detector.cpp index 3366314..f72f673 100644 --- a/src/gpd/grasp_detector.cpp +++ b/src/gpd/grasp_detector.cpp @@ -139,7 +139,9 @@ std::vector GraspDetector::detectGrasps(const CloudCamera& cloud_cam) if (plot_filtered_grasps_) { - plotter.plotFingers(candidates, cloud_cam.getCloudProcessed(), "Filtered Grasps"); + const HandSearch::Parameters& params = candidates_generator_->getHandSearchParams(); + plotter.plotFingers3D(candidates, cloud_cam.getCloudOriginal(), "Valid Grasps", params.hand_outer_diameter_, + params.finger_width_, params.hand_depth_, params.hand_height_); } } @@ -150,7 +152,9 @@ std::vector GraspDetector::detectGrasps(const CloudCamera& cloud_cam) if (plot_filtered_grasps_) { - plotter.plotFingers(candidates, cloud_cam.getCloudProcessed(), "Filtered Grasps"); + const HandSearch::Parameters& params = candidates_generator_->getHandSearchParams(); + plotter.plotFingers3D(candidates, cloud_cam.getCloudOriginal(), "Valid Grasps", params.hand_outer_diameter_, + params.finger_width_, params.hand_depth_, params.hand_height_); } } @@ -179,7 +183,9 @@ std::vector GraspDetector::detectGrasps(const CloudCamera& cloud_cam) if (plot_clusters_) { - plotter.plotFingers(clustered_grasps, cloud_cam.getCloudOriginal(), "Clustered Grasps (Original Point Cloud)"); + const HandSearch::Parameters& params = candidates_generator_->getHandSearchParams(); + plotter.plotFingers3D(clustered_grasps, cloud_cam.getCloudOriginal(), "Valid Grasps", params.hand_outer_diameter_, + params.finger_width_, params.hand_depth_, params.hand_height_); } } else @@ -211,7 +217,9 @@ std::vector GraspDetector::detectGrasps(const CloudCamera& cloud_cam) if (plot_selected_grasps_) { - plotter.plotFingers(selected_grasps, cloud_cam.getCloudOriginal(), "Selected Grasps (Original Point Cloud)"); + const HandSearch::Parameters& params = candidates_generator_->getHandSearchParams(); + plotter.plotFingers3D(selected_grasps, cloud_cam.getCloudOriginal(), "Valid Grasps", params.hand_outer_diameter_, + params.finger_width_, params.hand_depth_, params.hand_height_); } return selected_grasps; @@ -312,7 +320,9 @@ std::vector GraspDetector::classifyGraspCandidates(const CloudCamera& clo if (plot_valid_grasps_) { Plot plotter; - plotter.plotFingers(valid_grasps, cloud_cam.getCloudOriginal(), "Valid Grasps"); + const HandSearch::Parameters& params = candidates_generator_->getHandSearchParams(); + plotter.plotFingers3D(valid_grasps, cloud_cam.getCloudOriginal(), "Valid Grasps", params.hand_outer_diameter_, + params.finger_width_, params.hand_depth_, params.hand_height_); } return valid_grasps;