Skip to content

Commit

Permalink
Remove deprecated headers. Update visualization.
Browse files Browse the repository at this point in the history
  • Loading branch information
atenpas committed Nov 23, 2017
1 parent 303e8aa commit 32f08ca
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 41 deletions.
22 changes: 0 additions & 22 deletions include/gpd/layer.h

This file was deleted.

13 changes: 0 additions & 13 deletions include/gpd/net.h

This file was deleted.

2 changes: 1 addition & 1 deletion launch/classify_candidates_file_15_channels.launch
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
<rosparam param="camera_position"> [0, 0, 0] </rosparam> <!-- The position of the camera -->

<!-- General parameters -->
<param name="num_samples" value="4000" /> <!-- The number of samples to draw from the point cloud -->
<param name="num_samples" value="5" /> <!-- The number of samples to draw from the point cloud -->
<param name="num_threads" value="4" /> <!-- The number of CPU threads to be used -->

<!-- Parameters for local grasp candidate search -->
Expand Down
20 changes: 15 additions & 5 deletions src/gpd/grasp_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,9 @@ std::vector<Grasp> 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_);
}
}

Expand All @@ -150,7 +152,9 @@ std::vector<Grasp> 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_);
}
}

Expand Down Expand Up @@ -179,7 +183,9 @@ std::vector<Grasp> 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
Expand Down Expand Up @@ -211,7 +217,9 @@ std::vector<Grasp> 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;
Expand Down Expand Up @@ -312,7 +320,9 @@ std::vector<Grasp> 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;
Expand Down

0 comments on commit 32f08ca

Please sign in to comment.