6060// Parameter loading
6161#include < rosparam_shortcuts/rosparam_shortcuts.h>
6262
63+ #include < tf2_eigen/tf2_eigen.h>
6364namespace moveit_grasps_demo
6465{
6566static 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
0 commit comments