Skip to content

Commit 8ec6a53

Browse files
committed
Disable suction voxels individually using collision checking
1 parent 7fb2250 commit 8ec6a53

File tree

6 files changed

+120
-105
lines changed

6 files changed

+120
-105
lines changed

include/moveit_grasps/suction_grasp_candidate.h

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -65,15 +65,22 @@ class SuctionGraspCandidate : public GraspCandidate
6565

6666
void setSuctionVoxelOverlap(std::vector<double> suction_voxel_overlap);
6767

68+
void setSuctionVoxelInCollision(std::vector<bool> voxel_in_collision);
69+
6870
std::vector<double> getSuctionVoxelOverlap();
6971

7072
std::vector<bool> getSuctionVoxelEnabled(double cutoff);
7173

74+
std::vector<bool> getSuctionVoxelInCollision();
75+
7276
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
7377
protected:
7478
// A vector of fractions maped to suction gripper voxels. [0,1] representing the fraction of the
7579
// suction voxel that overlaps the object
7680
std::vector<double> suction_voxel_overlap_;
81+
// Whether the voxel is colliding with any objects other than the target.
82+
// If it is, then using the voxel risks attaching to other unintended objects
83+
std::vector<bool> voxel_in_collision_;
7784

7885
}; // class
7986

include/moveit_grasps/suction_grasp_filter.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -103,13 +103,13 @@ class SuctionGraspFilter : public GraspFilter
103103
const planning_scene::PlanningScenePtr& planning_scene);
104104

105105
/**
106-
* \brief Add a collision object in the location of every active suction voxel. This is used for collision
106+
* \brief Add a collision object in the location of active suction voxel. This is used for collision
107107
* checking between the suction cups and other objects in the scene that you do not want to pick up
108108
* \param grasp_data - A pointer to a SuctionGraspData with a populated SuctionVoxelMatrix
109109
* \param planning_scene - A pointer to a planning scene where we will attach the collision objects
110110
* \param collision_object_names - Output, the collision object names added to the planning scene
111111
*/
112-
bool attachActiveSuctionCupCO(const SuctionGraspDataPtr& grasp_data, const std::vector<bool>& suction_voxel_enabled,
112+
bool attachAllSuctionCupCO(const SuctionGraspDataPtr& grasp_data,
113113
const planning_scene::PlanningScenePtr& planning_scene,
114114
std::vector<std::string>& collision_object_names);
115115

src/demo/suction_grasp_pipeline_demo.cpp

Lines changed: 18 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,7 @@
6060
// Parameter loading
6161
#include <rosparam_shortcuts/rosparam_shortcuts.h>
6262

63+
#include <tf2_eigen/tf2_eigen.h>
6364
namespace moveit_grasps_demo
6465
{
6566
static const std::string LOGNAME = "grasp_pipeline_demo";
@@ -114,11 +115,10 @@ class GraspPipelineDemo
114115
"grasping_planning_scene");
115116
planning_scene_monitor_->getPlanningScene()->setName("grasping_planning_scene");
116117

117-
robot_model_loader::RobotModelLoaderPtr robot_model_loader;
118-
robot_model_loader = std::make_shared<robot_model_loader::RobotModelLoader>("robot_description");
118+
robot_model_loader_ = std::make_shared<robot_model_loader::RobotModelLoader>("robot_description");
119119

120120
// Load the robot model
121-
robot_model_ = robot_model_loader->getModel();
121+
robot_model_ = robot_model_loader_->getModel();
122122
arm_jmg_ = robot_model_->getJointModelGroup(planning_group_name_);
123123

124124
// ---------------------------------------------------------------------------------------------
@@ -413,9 +413,9 @@ class GraspPipelineDemo
413413
double& y_width, double& z_height)
414414
{
415415
// Generate random cuboid
416-
double xmin = 0.125;
416+
double xmin = 0.225;
417417
double xmax = 0.250;
418-
double ymin = 0.125;
418+
double ymin = 0.225;
419419
double ymax = 0.250;
420420
double zmin = 0.200;
421421
double zmax = 0.500;
@@ -437,14 +437,22 @@ class GraspPipelineDemo
437437

438438
object_name = "pick_target";
439439
visual_tools_->generateRandomCuboid(object_pose, x_depth, y_width, z_height, pose_bounds, cuboid_bounds);
440-
visual_tools_->publishCollisionCuboid(object_pose, x_depth, y_width, z_height, object_name, rviz_visual_tools::RED);
440+
visual_tools_->publishCollisionCuboid(object_pose, x_depth, y_width, z_height, object_name, rviz_visual_tools::BLUE);
441441
visual_tools_->publishAxis(object_pose, rviz_visual_tools::MEDIUM);
442442
visual_tools_->trigger();
443443

444+
Eigen::Isometry3d pose_eigen;
445+
Eigen::fromMsg(object_pose, pose_eigen);
446+
visual_tools_->publishCollisionCuboid(pose_eigen * Eigen::Translation3d(x_depth, 0.0, 0.0), x_depth, y_width, z_height, "box_plus_x", rviz_visual_tools::RED);
447+
visual_tools_->publishCollisionCuboid(pose_eigen * Eigen::Translation3d(-x_depth, 0.0, 0.0), x_depth, y_width, z_height, "box_minus_x", rviz_visual_tools::RED);
448+
visual_tools_->publishCollisionCuboid(pose_eigen * Eigen::Translation3d(0.0, y_width, 0.0), x_depth, y_width, z_height, "box_plus_y", rviz_visual_tools::RED);
449+
visual_tools_->publishCollisionCuboid(pose_eigen * Eigen::Translation3d(0.0, -y_width, 0.0), x_depth, y_width, z_height, "box_minus_y", rviz_visual_tools::RED);
450+
visual_tools_->trigger();
451+
444452
bool success = true;
445453
double timeout = 5; // seconds
446454
ros::Rate rate(100);
447-
while (success && !planning_scene_monitor_->getPlanningScene()->knowsFrameTransform(object_name))
455+
while (success && !planning_scene_monitor_->getPlanningScene()->knowsFrameTransform(object_name) && !planning_scene_monitor_->getPlanningScene()->knowsFrameTransform("box_minus_y"))
448456
{
449457
rate.sleep();
450458
success = rate.cycleTime().toSec() < timeout;
@@ -456,6 +464,9 @@ class GraspPipelineDemo
456464
// A shared node handle
457465
ros::NodeHandle nh_;
458466

467+
// Robot model loader
468+
robot_model_loader::RobotModelLoaderPtr robot_model_loader_;
469+
459470
// Tool for visualizing things in Rviz
460471
moveit_visual_tools::MoveItVisualToolsPtr visual_tools_;
461472

src/suction_grasp_candidate.cpp

Lines changed: 14 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@ SuctionGraspCandidate::SuctionGraspCandidate(const moveit_msgs::Grasp& grasp, co
4444
const Eigen::Isometry3d& cuboid_pose)
4545
: GraspCandidate::GraspCandidate(grasp, std::dynamic_pointer_cast<GraspData>(grasp_data), cuboid_pose)
4646
, suction_voxel_overlap_(grasp_data->suction_voxel_matrix_->getNumVoxels())
47+
, voxel_in_collision_(grasp_data->suction_voxel_matrix_->getNumVoxels())
4748
{
4849
}
4950

@@ -57,11 +58,23 @@ std::vector<double> SuctionGraspCandidate::getSuctionVoxelOverlap()
5758
return suction_voxel_overlap_;
5859
}
5960

61+
void SuctionGraspCandidate::setSuctionVoxelInCollision(std::vector<bool> voxel_in_collision)
62+
{
63+
voxel_in_collision_ = voxel_in_collision;
64+
}
65+
66+
std::vector<bool> SuctionGraspCandidate::getSuctionVoxelInCollision()
67+
{
68+
return voxel_in_collision_;
69+
}
70+
6071
std::vector<bool> SuctionGraspCandidate::getSuctionVoxelEnabled(double suction_voxel_cutoff)
6172
{
6273
std::vector<bool> suction_voxel_enabled(suction_voxel_overlap_.size());
6374
for (std::size_t voxel_ix = 0; voxel_ix < suction_voxel_enabled.size(); ++voxel_ix)
64-
suction_voxel_enabled[voxel_ix] = suction_voxel_overlap_[voxel_ix] >= suction_voxel_cutoff;
75+
{
76+
suction_voxel_enabled[voxel_ix] = (suction_voxel_overlap_[voxel_ix] >= suction_voxel_cutoff && !voxel_in_collision_[voxel_ix]);
77+
}
6578
return suction_voxel_enabled;
6679
}
6780

0 commit comments

Comments
 (0)