47 #include <visualization_msgs/MarkerArray.h> 
   49 #include <gmock/gmock.h> 
   50 #include <gtest/gtest.h> 
   51 #include <urdf_parser/urdf_parser.h> 
   89     std::map<std::string, moveit::core::SolverAllocatorFn> allocators;
 
  106   planning_scene::PlanningScenePtr 
ps_;
 
  122   moveit_msgs::JointConstraint jcm1;
 
  124   jcm1.position = 0.42;
 
  125   jcm1.tolerance_above = 0.01;
 
  126   jcm1.tolerance_below = 0.05;
 
  130   std::vector<kinematic_constraints::JointConstraint> js;
 
  138   jcm1.joint_name = 
"r_shoulder_pan_joint";
 
  143   EXPECT_EQ(jcs.getUnconstrainedJointCount(), 6u);
 
  146   for (
int t = 0; 
t < 100; ++
t)
 
  154   EXPECT_EQ(jcs.getUnconstrainedJointCount(), 6u);
 
  158   moveit_msgs::JointConstraint jcm2;
 
  159   jcm2.joint_name = 
"r_shoulder_pan_joint";
 
  160   jcm2.position = 0.54;
 
  161   jcm2.tolerance_above = 0.01;
 
  162   jcm2.tolerance_below = 0.01;
 
  184   jcm1.tolerance_above = .05;
 
  185   jcm1.tolerance_below = .05;
 
  187   jcm2.tolerance_above = .1;
 
  188   jcm2.tolerance_below = .1;
 
  197   for (
int t = 0; 
t < 100; ++
t)
 
  206   jcm1.position = -3.1;
 
  207   jcm1.tolerance_above = .05;
 
  208   jcm1.tolerance_below = .05;
 
  218   jcm1.tolerance_above = .05;
 
  219   jcm1.tolerance_below = .05;
 
  221   jcm2.tolerance_above = .05;
 
  222   jcm2.tolerance_below = .05;
 
  230   for (
int t = 0; 
t < 100; ++
t)
 
  233     std::map<std::string, double> var_values;
 
  247   for (
int t = 0; 
t < 100; ++
t)
 
  260   moveit_msgs::PositionConstraint pcm;
 
  262   pcm.link_name = 
"l_wrist_roll_link";
 
  263   pcm.target_point_offset.x = 0;
 
  264   pcm.target_point_offset.y = 0;
 
  265   pcm.target_point_offset.z = 0;
 
  266   pcm.constraint_region.primitives.resize(1);
 
  267   pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
 
  268   pcm.constraint_region.primitives[0].dimensions.resize(1);
 
  269   pcm.constraint_region.primitives[0].dimensions[0] = 0.001;
 
  271   pcm.constraint_region.primitive_poses.resize(1);
 
  272   pcm.constraint_region.primitive_poses[0].position.x = 0.55;
 
  273   pcm.constraint_region.primitive_poses[0].position.y = 0.2;
 
  274   pcm.constraint_region.primitive_poses[0].position.z = 1.25;
 
  275   pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
 
  276   pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
 
  277   pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
 
  278   pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
 
  292   pcm.header.frame_id = robot_model_->getModelFrame();
 
  302   pcm.link_name = 
"l_shoulder_pan_link";
 
  308   pcm.link_name = 
"l_wrist_roll_link";
 
  330   moveit_msgs::OrientationConstraint ocm;
 
  332   ocm.link_name = 
"r_wrist_roll_link";
 
  333   ocm.header.frame_id = ocm.link_name;
 
  334   ocm.orientation.x = 0.5;
 
  335   ocm.orientation.y = 0.5;
 
  336   ocm.orientation.z = 0.5;
 
  337   ocm.orientation.w = 0.5;
 
  338   ocm.absolute_x_axis_tolerance = 0.01;
 
  339   ocm.absolute_y_axis_tolerance = 0.01;
 
  340   ocm.absolute_z_axis_tolerance = 0.01;
 
  342   ocm.parameterization = moveit_msgs::OrientationConstraint::XYZ_EULER_ANGLES;
 
  349   ocm.header.frame_id = robot_model_->getModelFrame();
 
  354   for (
int t = 0; 
t < 100; ++
t)
 
  362   ocm.parameterization = moveit_msgs::OrientationConstraint::ROTATION_VECTOR;
 
  366   for (
int t = 0; 
t < 100; ++
t)
 
  386   moveit_msgs::PositionConstraint pcm;
 
  388   pcm.link_name = 
"l_wrist_roll_link";
 
  389   pcm.target_point_offset.x = 0;
 
  390   pcm.target_point_offset.y = 0;
 
  391   pcm.target_point_offset.z = 0;
 
  392   pcm.constraint_region.primitives.resize(1);
 
  393   pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
 
  394   pcm.constraint_region.primitives[0].dimensions.resize(1);
 
  395   pcm.constraint_region.primitives[0].dimensions[0] = 0.001;
 
  397   pcm.header.frame_id = robot_model_->getModelFrame();
 
  399   pcm.constraint_region.primitive_poses.resize(1);
 
  400   pcm.constraint_region.primitive_poses[0].position.x = 0.55;
 
  401   pcm.constraint_region.primitive_poses[0].position.y = 0.2;
 
  402   pcm.constraint_region.primitive_poses[0].position.z = 1.25;
 
  403   pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
 
  404   pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
 
  405   pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
 
  406   pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
 
  412   moveit_msgs::OrientationConstraint ocm;
 
  414   ocm.link_name = 
"l_wrist_roll_link";
 
  415   ocm.header.frame_id = robot_model_->getModelFrame();
 
  416   ocm.orientation.x = 0.0;
 
  417   ocm.orientation.y = 0.0;
 
  418   ocm.orientation.z = 0.0;
 
  419   ocm.orientation.w = 1.0;
 
  420   ocm.absolute_x_axis_tolerance = 0.2;
 
  421   ocm.absolute_y_axis_tolerance = 0.1;
 
  422   ocm.absolute_z_axis_tolerance = 0.4;
 
  429   for (
int t = 0; 
t < 100; ++
t)
 
  438   for (
int t = 0; 
t < 100; ++
t)
 
  446   for (
int t = 0; 
t < 100; ++
t)
 
  467   std::map<std::string, double> state_values;
 
  469   moveit_msgs::JointConstraint torso_constraint;
 
  470   torso_constraint.joint_name = 
"torso_lift_joint";
 
  472   torso_constraint.tolerance_above = 0.01;
 
  473   torso_constraint.tolerance_below = 0.01;
 
  474   torso_constraint.weight = 1.0;
 
  478   moveit_msgs::JointConstraint jcm2;
 
  479   jcm2.joint_name = 
"r_elbow_flex_joint";
 
  481   jcm2.tolerance_above = 0.01;
 
  482   jcm2.tolerance_below = 0.01;
 
  486   moveit_msgs::PositionConstraint pcm;
 
  488   pcm.link_name = 
"l_wrist_roll_link";
 
  489   pcm.target_point_offset.x = 0;
 
  490   pcm.target_point_offset.y = 0;
 
  491   pcm.target_point_offset.z = 0;
 
  492   pcm.constraint_region.primitives.resize(1);
 
  493   pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
 
  494   pcm.constraint_region.primitives[0].dimensions.resize(1);
 
  495   pcm.constraint_region.primitives[0].dimensions[0] = 0.001;
 
  497   pcm.constraint_region.primitive_poses.resize(1);
 
  498   pcm.constraint_region.primitive_poses[0].position.x = 0.55;
 
  499   pcm.constraint_region.primitive_poses[0].position.y = 0.2;
 
  500   pcm.constraint_region.primitive_poses[0].position.z = 1.25;
 
  501   pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
 
  502   pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
 
  503   pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
 
  504   pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
 
  507   pcm.header.frame_id = robot_model_->getModelFrame();
 
  509   moveit_msgs::OrientationConstraint ocm;
 
  511   ocm.link_name = 
"l_wrist_roll_link";
 
  512   ocm.header.frame_id = robot_model_->getModelFrame();
 
  513   ocm.orientation.x = 0.0;
 
  514   ocm.orientation.y = 0.0;
 
  515   ocm.orientation.z = 0.0;
 
  516   ocm.orientation.w = 1.0;
 
  517   ocm.absolute_x_axis_tolerance = 0.2;
 
  518   ocm.absolute_y_axis_tolerance = 0.1;
 
  519   ocm.absolute_z_axis_tolerance = 0.4;
 
  522   std::vector<kinematic_constraints::JointConstraint> js;
 
  525   constraint_samplers::JointConstraintSamplerPtr jcsp(
 
  529   std::vector<kinematic_constraints::JointConstraint> js2;
 
  545   std::vector<constraint_samplers::ConstraintSamplerPtr> cspv;
 
  546   cspv.push_back(jcsp2);
 
  547   cspv.push_back(iksp);
 
  548   cspv.push_back(jcsp);
 
  563   for (
int t = 0; 
t < 100; ++
t)
 
  575   pcm.link_name = 
"r_wrist_roll_link";
 
  576   ocm.link_name = 
"r_wrist_roll_link";
 
  591   cspv.push_back(iksp2);
 
  592   cspv.push_back(iksp);
 
  598   ASSERT_TRUE(ikcs_test);
 
  602   pcm.link_name = 
"l_wrist_roll_link";
 
  603   ocm.link_name = 
"l_wrist_roll_link";
 
  604   pcm.header.frame_id = 
"r_wrist_roll_link";
 
  605   ocm.header.frame_id = 
"r_wrist_roll_link";
 
  611   cspv.push_back(iksp2);
 
  612   cspv.push_back(iksp);
 
  632   moveit_msgs::PositionConstraint pcm;
 
  633   pcm.link_name = 
"l_wrist_roll_link";
 
  634   pcm.target_point_offset.x = 0;
 
  635   pcm.target_point_offset.y = 0;
 
  636   pcm.target_point_offset.z = 0;
 
  637   pcm.constraint_region.primitives.resize(1);
 
  638   pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
 
  639   pcm.constraint_region.primitives[0].dimensions.resize(1);
 
  640   pcm.constraint_region.primitives[0].dimensions[0] = 0.001;
 
  642   pcm.header.frame_id = robot_model_->getModelFrame();
 
  644   pcm.constraint_region.primitive_poses.resize(1);
 
  645   pcm.constraint_region.primitive_poses[0].position.x = 0.55;
 
  646   pcm.constraint_region.primitive_poses[0].position.y = 0.2;
 
  647   pcm.constraint_region.primitive_poses[0].position.z = 1.25;
 
  648   pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
 
  649   pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
 
  650   pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
 
  651   pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
 
  654   moveit_msgs::OrientationConstraint ocm;
 
  656   ocm.link_name = 
"l_wrist_roll_link";
 
  657   ocm.header.frame_id = robot_model_->getModelFrame();
 
  658   ocm.orientation.x = 0.0;
 
  659   ocm.orientation.y = 0.0;
 
  660   ocm.orientation.z = 0.0;
 
  661   ocm.orientation.w = 1.0;
 
  662   ocm.absolute_x_axis_tolerance = 0.2;
 
  663   ocm.absolute_y_axis_tolerance = 0.1;
 
  664   ocm.absolute_z_axis_tolerance = 0.4;
 
  668   moveit_msgs::Constraints c;
 
  669   c.position_constraints.push_back(pcm);
 
  670   c.orientation_constraints.push_back(ocm);
 
  672   constraint_samplers::ConstraintSamplerPtr 
s =
 
  680   static const int NT = 100;
 
  682   for (
int t = 0; 
t < NT; ++
t)
 
  687     if (
s->sample(ks, ks_const, 1))
 
  690   ROS_INFO(
"Success rate for IK Constraint Sampler with position & orientation constraints for one arm: %lf",
 
  691            (
double)succ / (
double)NT);
 
  694   ocm.absolute_x_axis_tolerance = 0.1;
 
  696   c.orientation_constraints.push_back(ocm);
 
  713   moveit_msgs::Constraints con;
 
  714   con.joint_constraints.resize(1);
 
  716   con.joint_constraints[0].joint_name = 
"l_shoulder_pan_joint";
 
  717   con.joint_constraints[0].position = 0.54;
 
  718   con.joint_constraints[0].tolerance_above = 0.01;
 
  719   con.joint_constraints[0].tolerance_below = 0.01;
 
  720   con.joint_constraints[0].weight = 1.0;
 
  722   constraint_samplers::ConstraintSamplerPtr 
s =
 
  728   con.joint_constraints.resize(7);
 
  730   con.joint_constraints[1].joint_name = 
"l_shoulder_lift_joint";
 
  731   con.joint_constraints[1].position = 0.54;
 
  732   con.joint_constraints[1].tolerance_above = 0.01;
 
  733   con.joint_constraints[1].tolerance_below = 0.01;
 
  734   con.joint_constraints[1].weight = 1.0;
 
  736   con.joint_constraints[2].joint_name = 
"l_upper_arm_roll_joint";
 
  737   con.joint_constraints[2].position = 0.54;
 
  738   con.joint_constraints[2].tolerance_above = 0.01;
 
  739   con.joint_constraints[2].tolerance_below = 0.01;
 
  740   con.joint_constraints[2].weight = 1.0;
 
  742   con.joint_constraints[3].joint_name = 
"l_elbow_flex_joint";
 
  743   con.joint_constraints[3].position = -0.54;
 
  744   con.joint_constraints[3].tolerance_above = 0.01;
 
  745   con.joint_constraints[3].tolerance_below = 0.01;
 
  746   con.joint_constraints[3].weight = 1.0;
 
  748   con.joint_constraints[4].joint_name = 
"l_forearm_roll_joint";
 
  749   con.joint_constraints[4].position = 0.54;
 
  750   con.joint_constraints[4].tolerance_above = 0.01;
 
  751   con.joint_constraints[4].tolerance_below = 0.01;
 
  752   con.joint_constraints[4].weight = 1.0;
 
  754   con.joint_constraints[5].joint_name = 
"l_wrist_flex_joint";
 
  755   con.joint_constraints[5].position = -0.54;
 
  756   con.joint_constraints[5].tolerance_above = 0.05;
 
  757   con.joint_constraints[5].tolerance_below = 0.05;
 
  758   con.joint_constraints[5].weight = 1.0;
 
  761   con.joint_constraints[6].joint_name = 
"l_wrist_flex_joint";
 
  762   con.joint_constraints[6].position = -0.56;
 
  763   con.joint_constraints[6].tolerance_above = 0.01;
 
  764   con.joint_constraints[6].tolerance_below = 0.01;
 
  765   con.joint_constraints[6].weight = 1.0;
 
  770   con.position_constraints.resize(1);
 
  773   con.position_constraints[0].link_name = 
"r_wrist_roll_link";
 
  774   con.position_constraints[0].target_point_offset.x = 0;
 
  775   con.position_constraints[0].target_point_offset.y = 0;
 
  776   con.position_constraints[0].target_point_offset.z = 0;
 
  777   con.position_constraints[0].constraint_region.primitives.resize(1);
 
  778   con.position_constraints[0].constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
 
  779   con.position_constraints[0].constraint_region.primitives[0].dimensions.resize(1);
 
  780   con.position_constraints[0].constraint_region.primitives[0].dimensions[0] = 0.001;
 
  782   con.position_constraints[0].header.frame_id = robot_model_->getModelFrame();
 
  784   con.position_constraints[0].constraint_region.primitive_poses.resize(1);
 
  785   con.position_constraints[0].constraint_region.primitive_poses[0].position.x = 0.55;
 
  786   con.position_constraints[0].constraint_region.primitive_poses[0].position.y = 0.2;
 
  787   con.position_constraints[0].constraint_region.primitive_poses[0].position.z = 1.25;
 
  788   con.position_constraints[0].constraint_region.primitive_poses[0].orientation.x = 0.0;
 
  789   con.position_constraints[0].constraint_region.primitive_poses[0].orientation.y = 0.0;
 
  790   con.position_constraints[0].constraint_region.primitive_poses[0].orientation.z = 0.0;
 
  791   con.position_constraints[0].constraint_region.primitive_poses[0].orientation.w = 1.0;
 
  792   con.position_constraints[0].weight = 1.0;
 
  801   con.position_constraints[0].link_name = 
"l_wrist_roll_link";
 
  814   con.orientation_constraints.resize(1);
 
  817   con.orientation_constraints[0].link_name = 
"r_wrist_roll_link";
 
  818   con.orientation_constraints[0].header.frame_id = robot_model_->getModelFrame();
 
  819   con.orientation_constraints[0].orientation.x = 0.0;
 
  820   con.orientation_constraints[0].orientation.y = 0.0;
 
  821   con.orientation_constraints[0].orientation.z = 0.0;
 
  822   con.orientation_constraints[0].orientation.w = 1.0;
 
  823   con.orientation_constraints[0].absolute_x_axis_tolerance = 0.2;
 
  824   con.orientation_constraints[0].absolute_y_axis_tolerance = 0.1;
 
  825   con.orientation_constraints[0].absolute_z_axis_tolerance = 0.4;
 
  826   con.orientation_constraints[0].weight = 1.0;
 
  841   con.orientation_constraints[0].link_name = 
"l_wrist_roll_link";
 
  853   con.position_constraints[0].link_name = 
"r_wrist_roll_link";
 
  855   ASSERT_TRUE(
static_cast<bool>(
s));
 
  863   con.joint_constraints.resize(8);
 
  864   con.joint_constraints[7].joint_name = 
"l_wrist_roll_joint";
 
  865   con.joint_constraints[7].position = 0.54;
 
  866   con.joint_constraints[7].tolerance_above = 0.01;
 
  867   con.joint_constraints[7].tolerance_below = 0.01;
 
  868   con.joint_constraints[7].weight = 1.0;
 
  885   moveit_msgs::Constraints con;
 
  886   con.joint_constraints.resize(1);
 
  888   con.joint_constraints[0].joint_name = 
"torso_lift_joint";
 
  890   con.joint_constraints[0].tolerance_above = 0.01;
 
  891   con.joint_constraints[0].tolerance_below = 0.01;
 
  892   con.joint_constraints[0].weight = 1.0;
 
  897   con.position_constraints.resize(1);
 
  899   con.position_constraints[0].link_name = 
"l_wrist_roll_link";
 
  900   con.position_constraints[0].target_point_offset.x = 0;
 
  901   con.position_constraints[0].target_point_offset.y = 0;
 
  902   con.position_constraints[0].target_point_offset.z = 0;
 
  903   con.position_constraints[0].constraint_region.primitives.resize(1);
 
  904   con.position_constraints[0].constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
 
  905   con.position_constraints[0].constraint_region.primitives[0].dimensions.resize(1);
 
  906   con.position_constraints[0].constraint_region.primitives[0].dimensions[0] = 0.001;
 
  908   con.position_constraints[0].constraint_region.primitive_poses.resize(1);
 
  909   con.position_constraints[0].constraint_region.primitive_poses[0].position.x = 0.55;
 
  910   con.position_constraints[0].constraint_region.primitive_poses[0].position.y = 0.2;
 
  911   con.position_constraints[0].constraint_region.primitive_poses[0].position.z = 1.25;
 
  912   con.position_constraints[0].constraint_region.primitive_poses[0].orientation.x = 0.0;
 
  913   con.position_constraints[0].constraint_region.primitive_poses[0].orientation.y = 0.0;
 
  914   con.position_constraints[0].constraint_region.primitive_poses[0].orientation.z = 0.0;
 
  915   con.position_constraints[0].constraint_region.primitive_poses[0].orientation.w = 1.0;
 
  916   con.position_constraints[0].weight = 1.0;
 
  918   con.position_constraints[0].header.frame_id = robot_model_->getModelFrame();
 
  920   con.orientation_constraints.resize(1);
 
  921   con.orientation_constraints[0].link_name = 
"l_wrist_roll_link";
 
  922   con.orientation_constraints[0].header.frame_id = robot_model_->getModelFrame();
 
  923   con.orientation_constraints[0].orientation.x = 0.0;
 
  924   con.orientation_constraints[0].orientation.y = 0.0;
 
  925   con.orientation_constraints[0].orientation.z = 0.0;
 
  926   con.orientation_constraints[0].orientation.w = 1.0;
 
  927   con.orientation_constraints[0].absolute_x_axis_tolerance = 0.2;
 
  928   con.orientation_constraints[0].absolute_y_axis_tolerance = 0.1;
 
  929   con.orientation_constraints[0].absolute_z_axis_tolerance = 0.4;
 
  930   con.orientation_constraints[0].weight = 1.0;
 
  932   constraint_samplers::ConstraintSamplerPtr 
s =
 
  941   ASSERT_TRUE(ikcs_test);
 
  943   for (
int t = 0; 
t < 1; ++
t)
 
  962   moveit_msgs::JointConstraint jcm1;
 
  963   jcm1.joint_name = 
"head_pan_joint";
 
  964   jcm1.position = 0.42;
 
  965   jcm1.tolerance_above = 0.01;
 
  966   jcm1.tolerance_below = 0.05;
 
  971   moveit_msgs::JointConstraint jcm2;
 
  972   jcm2.joint_name = 
"l_shoulder_pan_joint";
 
  974   jcm2.tolerance_above = 0.1;
 
  975   jcm2.tolerance_below = 0.05;
 
  980   moveit_msgs::JointConstraint jcm3;
 
  981   jcm3.joint_name = 
"r_wrist_roll_joint";
 
  983   jcm3.tolerance_above = 0.14;
 
  984   jcm3.tolerance_below = 0.005;
 
  989   moveit_msgs::JointConstraint jcm4;
 
  990   jcm4.joint_name = 
"torso_lift_joint";
 
  992   jcm4.tolerance_above = 0.09;
 
  993   jcm4.tolerance_below = 0.01;
 
  997   std::vector<kinematic_constraints::JointConstraint> js;
 
 1008   for (
int t = 0; 
t < 100; ++
t)
 
 1016   moveit_msgs::Constraints c;
 
 1019   constraint_samplers::ConstraintSamplerPtr s0 =
 
 1024   c.joint_constraints.push_back(jcm1);
 
 1025   c.joint_constraints.push_back(jcm2);
 
 1026   c.joint_constraints.push_back(jcm3);
 
 1027   c.joint_constraints.push_back(jcm4);
 
 1029   constraint_samplers::ConstraintSamplerPtr 
s =
 
 1034   for (
int t = 0; 
t < 1000; ++
t)
 
 1044   moveit_msgs::Constraints c;
 
 1046   moveit_msgs::PositionConstraint pcm;
 
 1047   pcm.link_name = 
"l_wrist_roll_link";
 
 1048   pcm.target_point_offset.x = 0;
 
 1049   pcm.target_point_offset.y = 0;
 
 1050   pcm.target_point_offset.z = 0;
 
 1052   pcm.constraint_region.primitives.resize(1);
 
 1053   pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
 
 1054   pcm.constraint_region.primitives[0].dimensions.resize(1);
 
 1055   pcm.constraint_region.primitives[0].dimensions[0] = 0.001;
 
 1057   pcm.header.frame_id = robot_model_->getModelFrame();
 
 1059   pcm.constraint_region.primitive_poses.resize(1);
 
 1060   pcm.constraint_region.primitive_poses[0].position.x = 0.55;
 
 1061   pcm.constraint_region.primitive_poses[0].position.y = 0.2;
 
 1062   pcm.constraint_region.primitive_poses[0].position.z = 1.25;
 
 1063   pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
 
 1064   pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
 
 1065   pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
 
 1066   pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
 
 1068   c.position_constraints.push_back(pcm);
 
 1070   moveit_msgs::OrientationConstraint ocm;
 
 1071   ocm.link_name = 
"l_wrist_roll_link";
 
 1072   ocm.header.frame_id = robot_model_->getModelFrame();
 
 1073   ocm.orientation.x = 0.0;
 
 1074   ocm.orientation.y = 0.0;
 
 1075   ocm.orientation.z = 0.0;
 
 1076   ocm.orientation.w = 1.0;
 
 1077   ocm.absolute_x_axis_tolerance = 0.2;
 
 1078   ocm.absolute_y_axis_tolerance = 0.1;
 
 1079   ocm.absolute_z_axis_tolerance = 0.4;
 
 1081   c.orientation_constraints.push_back(ocm);
 
 1083   ocm.link_name = 
"r_wrist_roll_link";
 
 1084   ocm.header.frame_id = robot_model_->getModelFrame();
 
 1085   ocm.orientation.x = 0.0;
 
 1086   ocm.orientation.y = 0.0;
 
 1087   ocm.orientation.z = 0.0;
 
 1088   ocm.orientation.w = 1.0;
 
 1089   ocm.absolute_x_axis_tolerance = 0.01;
 
 1090   ocm.absolute_y_axis_tolerance = 0.01;
 
 1091   ocm.absolute_z_axis_tolerance = 0.01;
 
 1093   c.orientation_constraints.push_back(ocm);
 
 1096   constraint_samplers::ConstraintSamplerPtr 
s =
 
 1113   static const int NT = 100;
 
 1115   for (
int t = 0; 
t < NT; ++
t)
 
 1119     if (
s->sample(ks, ks_const, 1))
 
 1123                  "Success rate for IK Constraint Sampler with position & orientation constraints for both arms: %lf",
 
 1124                  (
double)succ / (
double)NT);
 
 1132   moveit_msgs::JointConstraint jcm;
 
 1133   jcm.position = 0.42;
 
 1134   jcm.tolerance_above = 0.01;
 
 1135   jcm.tolerance_below = 0.05;
 
 1137   jcm.joint_name = 
"r_shoulder_pan_joint";
 
 1139   std::vector<kinematic_constraints::JointConstraint> js;
 
 1147   const std::vector<double> joint_positions_v(joint_positions, joint_positions + ks.
getVariableCount());
 
 1154   const std::vector<double> joint_positions_v2(joint_positions2, joint_positions2 + ks.
getVariableCount());
 
 1155   using namespace testing;
 
 1156   EXPECT_THAT(joint_positions_v, ContainerEq(joint_positions_v2));
 
 1164   const std::vector<double> joint_positions_v3(joint_positions3, joint_positions3 + ks.
getVariableCount());
 
 1165   EXPECT_THAT(joint_positions_v, Not(ContainerEq(joint_positions_v3)));
 
 1166   EXPECT_THAT(joint_positions_v2, Not(ContainerEq(joint_positions_v3)));
 
 1173   moveit_msgs::PositionConstraint pcm;
 
 1175   pcm.link_name = 
"l_wrist_roll_link";
 
 1176   pcm.target_point_offset.x = 0;
 
 1177   pcm.target_point_offset.y = 0;
 
 1178   pcm.target_point_offset.z = 0;
 
 1179   pcm.constraint_region.primitives.resize(1);
 
 1180   pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
 
 1181   pcm.constraint_region.primitives[0].dimensions.resize(1);
 
 1182   pcm.constraint_region.primitives[0].dimensions[0] = 0.001;
 
 1184   pcm.constraint_region.primitive_poses.resize(1);
 
 1185   pcm.constraint_region.primitive_poses[0].position.x = 0.55;
 
 1186   pcm.constraint_region.primitive_poses[0].position.y = 0.2;
 
 1187   pcm.constraint_region.primitive_poses[0].position.z = 1.25;
 
 1188   pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
 
 1189   pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
 
 1190   pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
 
 1191   pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
 
 1194   pcm.header.frame_id = robot_model_->getModelFrame();
 
 1208   const Eigen::Isometry3d root_to_left_tool1 = ks.
getFrameTransform(
"l_gripper_tool_frame", &found);
 
 1218   const Eigen::Isometry3d root_to_left_tool2 = ks.
getFrameTransform(
"l_gripper_tool_frame", &found);
 
 1229   const Eigen::Isometry3d root_to_left_tool3 = ks.
getFrameTransform(
"l_gripper_tool_frame", &found);
 
 1232   EXPECT_TRUE((root_to_left_tool1 * root_to_left_tool2.inverse()).matrix().isIdentity(1e-7));
 
 1233   EXPECT_FALSE((root_to_left_tool1 * root_to_left_tool3.inverse()).matrix().isIdentity(1e-7));
 
 1234   EXPECT_FALSE((root_to_left_tool2 * root_to_left_tool3.inverse()).matrix().isIdentity(1e-7));
 
 1239   testing::InitGoogleTest(&argc, argv);
 
 1240   ros::init(argc, argv, 
"test_constraint_samplers");
 
 1242   return RUN_ALL_TESTS();