00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/test_resources/config.h>
00038 #include <moveit/planning_scene/planning_scene.h>
00039 #include <moveit/kinematic_constraints/kinematic_constraint.h>
00040 #include <moveit/constraint_samplers/default_constraint_samplers.h>
00041 #include <moveit/constraint_samplers/union_constraint_sampler.h>
00042 #include <moveit/constraint_samplers/constraint_sampler_manager.h>
00043 #include <moveit/constraint_samplers/constraint_sampler_tools.h>
00044 #include <moveit_msgs/DisplayTrajectory.h>
00045 #include <moveit/robot_state/conversions.h>
00046
00047 #include <geometric_shapes/shape_operations.h>
00048 #include <visualization_msgs/MarkerArray.h>
00049
00050 #include <gtest/gtest.h>
00051 #include <urdf_parser/urdf_parser.h>
00052 #include <fstream>
00053 #include <boost/bind.hpp>
00054 #include <boost/filesystem/path.hpp>
00055
00056 #include "pr2_arm_kinematics_plugin.h"
00057
00058 class LoadPlanningModelsPr2 : public testing::Test
00059 {
00060 protected:
00061
00062 boost::shared_ptr<kinematics::KinematicsBase> getKinematicsSolverRightArm(const robot_model::JointModelGroup *jmg)
00063 {
00064 {
00065 return pr2_kinematics_plugin_right_arm_;
00066 }
00067 }
00068
00069 boost::shared_ptr<kinematics::KinematicsBase> getKinematicsSolverLeftArm(const robot_model::JointModelGroup *jmg)
00070 {
00071 {
00072 return pr2_kinematics_plugin_left_arm_;
00073 }
00074 }
00075
00076 virtual void SetUp()
00077 {
00078 srdf_model.reset(new srdf::Model());
00079 std::string xml_string;
00080 std::fstream xml_file((boost::filesystem::path(MOVEIT_TEST_RESOURCES_DIR) / "urdf/robot.xml").string().c_str(), std::fstream::in);
00081 if (xml_file.is_open())
00082 {
00083 while ( xml_file.good() )
00084 {
00085 std::string line;
00086 std::getline( xml_file, line);
00087 xml_string += (line + "\n");
00088 }
00089 xml_file.close();
00090 urdf_model = urdf::parseURDF(xml_string);
00091 }
00092 srdf_model->initFile(*urdf_model, (boost::filesystem::path(MOVEIT_TEST_RESOURCES_DIR) / "srdf/robot.xml").string());
00093 kmodel.reset(new robot_model::RobotModel(urdf_model, srdf_model));
00094
00095 pr2_kinematics_plugin_right_arm_.reset(new pr2_arm_kinematics::PR2ArmKinematicsPlugin);
00096
00097 pr2_kinematics_plugin_right_arm_->setRobotModel(urdf_model);
00098 pr2_kinematics_plugin_right_arm_->initialize("",
00099 "right_arm",
00100 "torso_lift_link",
00101 "r_wrist_roll_link",
00102 .01);
00103
00104 pr2_kinematics_plugin_left_arm_.reset(new pr2_arm_kinematics::PR2ArmKinematicsPlugin);
00105
00106 pr2_kinematics_plugin_left_arm_->setRobotModel(urdf_model);
00107 pr2_kinematics_plugin_left_arm_->initialize("",
00108 "left_arm",
00109 "torso_lift_link",
00110 "l_wrist_roll_link",
00111 .01);
00112
00113 func_right_arm.reset(new robot_model::SolverAllocatorFn(boost::bind(&LoadPlanningModelsPr2::getKinematicsSolverRightArm, this, _1)));
00114 func_left_arm.reset(new robot_model::SolverAllocatorFn(boost::bind(&LoadPlanningModelsPr2::getKinematicsSolverLeftArm, this, _1)));
00115
00116 std::map<std::string, robot_model::SolverAllocatorFn> allocators;
00117 allocators["right_arm"] = *func_right_arm;
00118 allocators["left_arm"] = *func_left_arm;
00119 allocators["whole_body"] = *func_right_arm;
00120 allocators["base"] = *func_left_arm;
00121
00122 kmodel->setKinematicsAllocators(allocators);
00123
00124 ps.reset(new planning_scene::PlanningScene(kmodel));
00125
00126 };
00127
00128 virtual void TearDown()
00129 {
00130 }
00131
00132 protected:
00133
00134 boost::shared_ptr<urdf::ModelInterface> urdf_model;
00135 boost::shared_ptr<srdf::Model> srdf_model;
00136 robot_model::RobotModelPtr kmodel;
00137 planning_scene::PlanningScenePtr ps;
00138 boost::shared_ptr<pr2_arm_kinematics::PR2ArmKinematicsPlugin> pr2_kinematics_plugin_right_arm_;
00139 boost::shared_ptr<pr2_arm_kinematics::PR2ArmKinematicsPlugin> pr2_kinematics_plugin_left_arm_;
00140 boost::shared_ptr<robot_model::SolverAllocatorFn> func_right_arm;
00141 boost::shared_ptr<robot_model::SolverAllocatorFn> func_left_arm;
00142 };
00143
00144 TEST_F(LoadPlanningModelsPr2, JointConstraintsSamplerSimple)
00145 {
00146 robot_state::RobotState ks(kmodel);
00147 ks.setToDefaultValues();
00148
00149 kinematic_constraints::JointConstraint jc1(kmodel);
00150 moveit_msgs::JointConstraint jcm1;
00151
00152 jcm1.position = 0.42;
00153 jcm1.tolerance_above = 0.01;
00154 jcm1.tolerance_below = 0.05;
00155 jcm1.weight = 1.0;
00156 EXPECT_FALSE(jc1.configure(jcm1));
00157
00158 std::vector<kinematic_constraints::JointConstraint> js;
00159 js.push_back(jc1);
00160
00161 constraint_samplers::JointConstraintSampler jcs(ps, "right_arm");
00162
00163 EXPECT_FALSE(jcs.configure(js));
00164
00165
00166 jcm1.joint_name = "r_shoulder_pan_joint";
00167 EXPECT_TRUE(jc1.configure(jcm1));
00168 js.push_back(jc1);
00169 EXPECT_TRUE(jcs.configure(js));
00170 EXPECT_EQ(jcs.getConstrainedJointCount(), 1);
00171 EXPECT_EQ(jcs.getUnconstrainedJointCount(), 6);
00172 EXPECT_TRUE(jcs.sample(ks.getJointStateGroup("right_arm"), ks, 1));
00173
00174 for (int t = 0 ; t < 100 ; ++t)
00175 {
00176 EXPECT_TRUE(jcs.sample(ks.getJointStateGroup("right_arm"), ks, 1));
00177 EXPECT_TRUE(jc1.decide(ks).satisfied);
00178 }
00179
00180
00181 EXPECT_TRUE(jcs.configure(js));
00182 EXPECT_EQ(jcs.getUnconstrainedJointCount(), 6);
00183
00184 kinematic_constraints::JointConstraint jc2(kmodel);
00185
00186 moveit_msgs::JointConstraint jcm2;
00187 jcm2.joint_name = "r_shoulder_pan_joint";
00188 jcm2.position = 0.54;
00189 jcm2.tolerance_above = 0.01;
00190 jcm2.tolerance_below = 0.01;
00191 jcm2.weight = 1.0;
00192 EXPECT_TRUE(jc2.configure(jcm2));
00193 js.push_back(jc2);
00194
00195
00196 EXPECT_FALSE(jcs.configure(js));
00197 EXPECT_FALSE(jcs.sample(ks.getJointStateGroup("right_arm"), ks, 1));
00198
00199
00200 constraint_samplers::JointConstraintSampler jcs2(ps, "arms");
00201 jcs2.configure(js);
00202 EXPECT_FALSE(jcs2.sample(ks.getJointStateGroup("right_arm"), ks, 1));
00203
00204
00205 constraint_samplers::JointConstraintSampler jcs3(ps, "left_arm");
00206 EXPECT_FALSE(jcs3.configure(js));
00207
00208
00209 js.clear();
00210
00211 jcm1.position = .4;
00212 jcm1.tolerance_above = .05;
00213 jcm1.tolerance_below = .05;
00214 jcm2.position = .4;
00215 jcm2.tolerance_above = .1;
00216 jcm2.tolerance_below = .1;
00217 EXPECT_TRUE(jc1.configure(jcm1));
00218 EXPECT_TRUE(jc2.configure(jcm2));
00219 js.push_back(jc1);
00220 js.push_back(jc2);
00221
00222 EXPECT_TRUE(jcs.configure(js));
00223
00224
00225 for (int t = 0 ; t < 100 ; ++t)
00226 {
00227 EXPECT_TRUE(jcs.sample(ks.getJointStateGroup("right_arm"), ks, 1));
00228 EXPECT_TRUE(jc1.decide(ks).satisfied);
00229 }
00230
00231
00232 js.clear();
00233
00234 jcm1.position = -3.1;
00235 jcm1.tolerance_above = .05;
00236 jcm1.tolerance_below = .05;
00237
00238
00239 EXPECT_TRUE(jc1.configure(jcm1));
00240 js.push_back(jc1);
00241 EXPECT_TRUE(jcs.configure(js));
00242
00243
00244 js.clear();
00245 jcm1.position = .35;
00246 jcm1.tolerance_above = .05;
00247 jcm1.tolerance_below = .05;
00248 jcm2.position = .45;
00249 jcm2.tolerance_above = .05;
00250 jcm2.tolerance_below = .05;
00251 EXPECT_TRUE(jc1.configure(jcm1));
00252 EXPECT_TRUE(jc2.configure(jcm2));
00253 js.push_back(jc1);
00254 js.push_back(jc2);
00255
00256
00257 EXPECT_TRUE(jcs.configure(js));
00258 for (int t = 0 ; t < 100 ; ++t)
00259 {
00260 EXPECT_TRUE(jcs.sample(ks.getJointStateGroup("right_arm"), ks, 1));
00261 std::map<std::string, double> var_values;
00262 ks.getJointStateGroup("right_arm")->getVariableValues(var_values);
00263 EXPECT_NEAR(var_values["r_shoulder_pan_joint"], .4, std::numeric_limits<double>::epsilon());
00264 EXPECT_TRUE(jc1.decide(ks).satisfied);
00265 EXPECT_TRUE(jc2.decide(ks).satisfied);
00266 }
00267
00268
00269 jcm1.position = .38;
00270 jcm2.position = .42;
00271 EXPECT_TRUE(jc1.configure(jcm1));
00272 EXPECT_TRUE(jc2.configure(jcm2));
00273 js.push_back(jc1);
00274 js.push_back(jc2);
00275 EXPECT_TRUE(jcs.configure(js));
00276 for (int t = 0 ; t < 100 ; ++t)
00277 {
00278 EXPECT_TRUE(jcs.sample(ks.getJointStateGroup("right_arm"), ks, 1));
00279 EXPECT_TRUE(jc1.decide(ks).satisfied);
00280 EXPECT_TRUE(jc2.decide(ks).satisfied);
00281 }
00282 }
00283
00284 TEST_F(LoadPlanningModelsPr2, IKConstraintsSamplerSimple)
00285 {
00286 robot_state::RobotState ks(kmodel);
00287 ks.setToDefaultValues();
00288 robot_state::Transforms &tf = ps->getTransformsNonConst();
00289
00290 kinematic_constraints::PositionConstraint pc(kmodel);
00291 moveit_msgs::PositionConstraint pcm;
00292
00293 pcm.link_name = "l_wrist_roll_link";
00294 pcm.target_point_offset.x = 0;
00295 pcm.target_point_offset.y = 0;
00296 pcm.target_point_offset.z = 0;
00297 pcm.constraint_region.primitives.resize(1);
00298 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
00299 pcm.constraint_region.primitives[0].dimensions.resize(1);
00300 pcm.constraint_region.primitives[0].dimensions[0] = 0.001;
00301
00302 pcm.constraint_region.primitive_poses.resize(1);
00303 pcm.constraint_region.primitive_poses[0].position.x = 0.55;
00304 pcm.constraint_region.primitive_poses[0].position.y = 0.2;
00305 pcm.constraint_region.primitive_poses[0].position.z = 1.25;
00306 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
00307 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
00308 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
00309 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
00310 pcm.weight = 1.0;
00311
00312 EXPECT_FALSE(pc.configure(pcm, tf));
00313
00314 constraint_samplers::IKConstraintSampler ik_bad(ps, "l_arm");
00315 EXPECT_FALSE(ik_bad.isValid());
00316
00317 constraint_samplers::IKConstraintSampler iks(ps, "left_arm");
00318 EXPECT_TRUE(iks.isValid());
00319
00320 EXPECT_FALSE(iks.configure(constraint_samplers::IKSamplingPose()));
00321
00322 EXPECT_FALSE(iks.configure(constraint_samplers::IKSamplingPose(pc)));
00323
00324 pcm.header.frame_id = kmodel->getModelFrame();
00325 EXPECT_TRUE(pc.configure(pcm, tf));
00326 EXPECT_TRUE(iks.configure(constraint_samplers::IKSamplingPose(pc)));
00327
00328
00329 constraint_samplers::IKConstraintSampler ik_bad_2(ps, "right_arm");
00330 EXPECT_TRUE(ik_bad_2.isValid());
00331 EXPECT_FALSE(ik_bad_2.configure(constraint_samplers::IKSamplingPose(pc)));
00332
00333
00334 pcm.link_name = "l_shoulder_pan_link";
00335 EXPECT_TRUE(pc.configure(pcm, tf));
00336 EXPECT_FALSE(iks.configure(constraint_samplers::IKSamplingPose(pc)));
00337
00338
00339 constraint_samplers::IKConstraintSampler ik_base(ps, "base");
00340 EXPECT_TRUE(ik_base.isValid());
00341 pcm.link_name = "l_wrist_roll_link";
00342 EXPECT_TRUE(pc.configure(pcm, tf));
00343 EXPECT_FALSE(ik_base.configure(constraint_samplers::IKSamplingPose(pc)));
00344
00345
00346 constraint_samplers::IKConstraintSampler ik_arms(ps, "arms");
00347 EXPECT_FALSE(iks.isValid());
00348 }
00349
00350
00351 TEST_F(LoadPlanningModelsPr2, OrientationConstraintsSampler)
00352 {
00353 robot_state::RobotState ks(kmodel);
00354 ks.setToDefaultValues();
00355 robot_state::Transforms &tf = ps->getTransformsNonConst();
00356
00357 kinematic_constraints::OrientationConstraint oc(kmodel);
00358 moveit_msgs::OrientationConstraint ocm;
00359
00360 ocm.link_name = "r_wrist_roll_link";
00361 ocm.header.frame_id = ocm.link_name;
00362 ocm.orientation.x = 0.5;
00363 ocm.orientation.y = 0.5;
00364 ocm.orientation.z = 0.5;
00365 ocm.orientation.w = 0.5;
00366 ocm.absolute_x_axis_tolerance = 0.01;
00367 ocm.absolute_y_axis_tolerance = 0.01;
00368 ocm.absolute_z_axis_tolerance = 0.01;
00369 ocm.weight = 1.0;
00370
00371 EXPECT_TRUE(oc.configure(ocm, tf));
00372
00373 bool p1 = oc.decide(ks).satisfied;
00374 EXPECT_FALSE(p1);
00375
00376 ocm.header.frame_id = kmodel->getModelFrame();
00377 EXPECT_TRUE(oc.configure(ocm, tf));
00378
00379 constraint_samplers::IKConstraintSampler iks(ps, "right_arm");
00380 EXPECT_TRUE(iks.configure(constraint_samplers::IKSamplingPose(oc)));
00381 for (int t = 0 ; t < 100; ++t)
00382 {
00383 EXPECT_TRUE(iks.sample(ks.getJointStateGroup("right_arm"), ks, 100));
00384 EXPECT_TRUE(oc.decide(ks).satisfied);
00385 }
00386 }
00387
00388 TEST_F(LoadPlanningModelsPr2, IKConstraintsSamplerValid)
00389 {
00390 robot_state::RobotState ks(kmodel);
00391 ks.setToDefaultValues();
00392 robot_state::Transforms &tf = ps->getTransformsNonConst();
00393
00394 kinematic_constraints::PositionConstraint pc(kmodel);
00395 moveit_msgs::PositionConstraint pcm;
00396
00397 pcm.link_name = "l_wrist_roll_link";
00398 pcm.target_point_offset.x = 0;
00399 pcm.target_point_offset.y = 0;
00400 pcm.target_point_offset.z = 0;
00401 pcm.constraint_region.primitives.resize(1);
00402 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
00403 pcm.constraint_region.primitives[0].dimensions.resize(1);
00404 pcm.constraint_region.primitives[0].dimensions[0] = 0.001;
00405
00406 pcm.header.frame_id = kmodel->getModelFrame();
00407
00408 pcm.constraint_region.primitive_poses.resize(1);
00409 pcm.constraint_region.primitive_poses[0].position.x = 0.55;
00410 pcm.constraint_region.primitive_poses[0].position.y = 0.2;
00411 pcm.constraint_region.primitive_poses[0].position.z = 1.25;
00412 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
00413 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
00414 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
00415 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
00416 pcm.weight = 1.0;
00417
00418 EXPECT_TRUE(pc.configure(pcm, tf));
00419
00420 kinematic_constraints::OrientationConstraint oc(kmodel);
00421 moveit_msgs::OrientationConstraint ocm;
00422
00423 ocm.link_name = "l_wrist_roll_link";
00424 ocm.header.frame_id = kmodel->getModelFrame();
00425 ocm.orientation.x = 0.0;
00426 ocm.orientation.y = 0.0;
00427 ocm.orientation.z = 0.0;
00428 ocm.orientation.w = 1.0;
00429 ocm.absolute_x_axis_tolerance = 0.2;
00430 ocm.absolute_y_axis_tolerance = 0.1;
00431 ocm.absolute_z_axis_tolerance = 0.4;
00432 ocm.weight = 1.0;
00433
00434 EXPECT_TRUE(oc.configure(ocm, tf));
00435
00436 constraint_samplers::IKConstraintSampler iks1(ps, "left_arm");
00437 EXPECT_TRUE(iks1.configure(constraint_samplers::IKSamplingPose(pc, oc)));
00438 for (int t = 0 ; t < 100 ; ++t)
00439 {
00440 EXPECT_TRUE(iks1.sample(ks.getJointStateGroup("left_arm"), ks, 100));
00441 EXPECT_TRUE(pc.decide(ks).satisfied);
00442 EXPECT_TRUE(oc.decide(ks).satisfied);
00443 }
00444
00445 constraint_samplers::IKConstraintSampler iks2(ps, "left_arm");
00446 EXPECT_TRUE(iks2.configure(constraint_samplers::IKSamplingPose(pc)));
00447 for (int t = 0 ; t < 100 ; ++t)
00448 {
00449 EXPECT_TRUE(iks2.sample(ks.getJointStateGroup("left_arm"), ks, 100));
00450 EXPECT_TRUE(pc.decide(ks).satisfied);
00451 }
00452
00453 constraint_samplers::IKConstraintSampler iks3(ps, "left_arm");
00454 EXPECT_TRUE(iks3.configure(constraint_samplers::IKSamplingPose(oc)));
00455 for (int t = 0 ; t < 100 ; ++t)
00456 {
00457 EXPECT_TRUE(iks3.sample(ks.getJointStateGroup("left_arm"), ks, 100));
00458 EXPECT_TRUE(oc.decide(ks).satisfied);
00459 }
00460 }
00461
00462 TEST_F(LoadPlanningModelsPr2, UnionConstraintSampler)
00463 {
00464 robot_state::RobotState ks(kmodel);
00465 ks.setToDefaultValues();
00466 robot_state::Transforms &tf = ps->getTransformsNonConst();
00467
00468 kinematic_constraints::JointConstraint jc1(kmodel);
00469
00470 std::map<std::string, double> state_values;
00471 ks.getStateValues(state_values);
00472
00473 moveit_msgs::JointConstraint torso_constraint;
00474 torso_constraint.joint_name = "torso_lift_joint";
00475 torso_constraint.position = state_values["torso_lift_joint"];
00476 torso_constraint.tolerance_above = 0.01;
00477 torso_constraint.tolerance_below = 0.01;
00478 torso_constraint.weight = 1.0;
00479 EXPECT_TRUE(jc1.configure(torso_constraint));
00480
00481 kinematic_constraints::JointConstraint jc2(kmodel);
00482 moveit_msgs::JointConstraint jcm2;
00483 jcm2.joint_name = "r_elbow_flex_joint";
00484 jcm2.position = state_values["r_elbow_flex_joint"];
00485 jcm2.tolerance_above = 0.01;
00486 jcm2.tolerance_below = 0.01;
00487 jcm2.weight = 1.0;
00488 EXPECT_TRUE(jc2.configure(jcm2));
00489
00490 moveit_msgs::PositionConstraint pcm;
00491
00492 pcm.link_name = "l_wrist_roll_link";
00493 pcm.target_point_offset.x = 0;
00494 pcm.target_point_offset.y = 0;
00495 pcm.target_point_offset.z = 0;
00496 pcm.constraint_region.primitives.resize(1);
00497 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
00498 pcm.constraint_region.primitives[0].dimensions.resize(1);
00499 pcm.constraint_region.primitives[0].dimensions[0] = 0.001;
00500
00501 pcm.constraint_region.primitive_poses.resize(1);
00502 pcm.constraint_region.primitive_poses[0].position.x = 0.55;
00503 pcm.constraint_region.primitive_poses[0].position.y = 0.2;
00504 pcm.constraint_region.primitive_poses[0].position.z = 1.25;
00505 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
00506 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
00507 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
00508 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
00509 pcm.weight = 1.0;
00510
00511 pcm.header.frame_id = kmodel->getModelFrame();
00512
00513 moveit_msgs::OrientationConstraint ocm;
00514
00515 ocm.link_name = "l_wrist_roll_link";
00516 ocm.header.frame_id = kmodel->getModelFrame();
00517 ocm.orientation.x = 0.0;
00518 ocm.orientation.y = 0.0;
00519 ocm.orientation.z = 0.0;
00520 ocm.orientation.w = 1.0;
00521 ocm.absolute_x_axis_tolerance = 0.2;
00522 ocm.absolute_y_axis_tolerance = 0.1;
00523 ocm.absolute_z_axis_tolerance = 0.4;
00524 ocm.weight = 1.0;
00525
00526 std::vector<kinematic_constraints::JointConstraint> js;
00527 js.push_back(jc1);
00528
00529 boost::shared_ptr<constraint_samplers::JointConstraintSampler> jcsp(new constraint_samplers::JointConstraintSampler(ps, "arms_and_torso"));
00530 EXPECT_TRUE(jcsp->configure(js));
00531
00532 std::vector<kinematic_constraints::JointConstraint> js2;
00533 js2.push_back(jc2);
00534
00535 boost::shared_ptr<constraint_samplers::JointConstraintSampler> jcsp2(new constraint_samplers::JointConstraintSampler(ps, "arms"));
00536 EXPECT_TRUE(jcsp2->configure(js2));
00537
00538 kinematic_constraints::PositionConstraint pc(kmodel);
00539 EXPECT_TRUE(pc.configure(pcm, tf));
00540
00541 kinematic_constraints::OrientationConstraint oc(kmodel);
00542 EXPECT_TRUE(oc.configure(ocm, tf));
00543
00544 boost::shared_ptr<constraint_samplers::IKConstraintSampler> iksp(new constraint_samplers::IKConstraintSampler(ps, "left_arm"));
00545 EXPECT_TRUE(iksp->isValid());
00546 EXPECT_TRUE(iksp->configure(constraint_samplers::IKSamplingPose(pc, oc)));
00547
00548 std::vector<constraint_samplers::ConstraintSamplerPtr> cspv;
00549 cspv.push_back(jcsp2);
00550 cspv.push_back(iksp);
00551 cspv.push_back(jcsp);
00552
00553 constraint_samplers::UnionConstraintSampler ucs(ps, "arms_and_torso", cspv);
00554
00555
00556 constraint_samplers::JointConstraintSampler* jcs = dynamic_cast<constraint_samplers::JointConstraintSampler*>(ucs.getSamplers()[0].get());
00557 EXPECT_TRUE(jcs);
00558 EXPECT_EQ(jcs->getJointModelGroup()->getName(), "arms_and_torso");
00559
00560 constraint_samplers::JointConstraintSampler* jcs2 = dynamic_cast<constraint_samplers::JointConstraintSampler*>(ucs.getSamplers()[1].get());
00561 EXPECT_TRUE(jcs2);
00562 EXPECT_EQ(jcs2->getJointModelGroup()->getName(), "arms");
00563
00564 for (int t = 0 ; t < 100; ++t)
00565 {
00566 EXPECT_TRUE(ucs.sample(ks.getJointStateGroup("arms_and_torso"), ks, 100));
00567 EXPECT_TRUE(jc1.decide(ks).satisfied);
00568 EXPECT_TRUE(jc2.decide(ks).satisfied);
00569 EXPECT_TRUE(pc.decide(ks).satisfied);
00570 }
00571
00572
00573 pcm.link_name = "r_wrist_roll_link";
00574 ocm.link_name = "r_wrist_roll_link";
00575 cspv.clear();
00576
00577 kinematic_constraints::PositionConstraint pc2(kmodel);
00578 EXPECT_TRUE(pc2.configure(pcm, tf));
00579
00580 kinematic_constraints::OrientationConstraint oc2(kmodel);
00581 EXPECT_TRUE(oc2.configure(ocm, tf));
00582
00583 boost::shared_ptr<constraint_samplers::IKConstraintSampler> iksp2(new constraint_samplers::IKConstraintSampler(ps, "right_arm"));
00584 EXPECT_TRUE(iksp2->isValid());
00585 EXPECT_TRUE(iksp2->configure(constraint_samplers::IKSamplingPose(pc2, oc2)));
00586
00587
00588 cspv.clear();
00589 cspv.push_back(iksp2);
00590 cspv.push_back(iksp);
00591
00592 constraint_samplers::UnionConstraintSampler ucs2(ps, "arms_and_torso", cspv);
00593
00594 constraint_samplers::IKConstraintSampler* ikcs_test = dynamic_cast<constraint_samplers::IKConstraintSampler*>(ucs2.getSamplers()[0].get());
00595 ASSERT_TRUE(ikcs_test);
00596 EXPECT_EQ(ikcs_test->getJointModelGroup()->getName(), "left_arm");
00597
00598
00599 pcm.link_name = "l_wrist_roll_link";
00600 ocm.link_name = "l_wrist_roll_link";
00601 pcm.header.frame_id = "r_wrist_roll_link";
00602 ocm.header.frame_id = "r_wrist_roll_link";
00603 EXPECT_TRUE(pc.configure(pcm, tf));
00604 EXPECT_TRUE(oc.configure(ocm, tf));
00605 ASSERT_TRUE(iksp->configure(constraint_samplers::IKSamplingPose(pc, oc)));
00606
00607 cspv.clear();
00608 cspv.push_back(iksp2);
00609 cspv.push_back(iksp);
00610
00611 constraint_samplers::UnionConstraintSampler ucs3(ps, "arms_and_torso", cspv);
00612
00613 ikcs_test = dynamic_cast<constraint_samplers::IKConstraintSampler*>(ucs3.getSamplers()[0].get());
00614 EXPECT_TRUE(ikcs_test);
00615 EXPECT_EQ(ikcs_test->getJointModelGroup()->getName(), "right_arm");
00616 }
00617
00618 TEST_F(LoadPlanningModelsPr2, PoseConstraintSamplerManager)
00619 {
00620 robot_state::RobotState ks(kmodel);
00621 ks.setToDefaultValues();
00622 robot_state::Transforms &tf = ps->getTransformsNonConst();
00623
00624 kinematic_constraints::PositionConstraint pc(kmodel);
00625
00626 moveit_msgs::PositionConstraint pcm;
00627 pcm.link_name = "l_wrist_roll_link";
00628 pcm.target_point_offset.x = 0;
00629 pcm.target_point_offset.y = 0;
00630 pcm.target_point_offset.z = 0;
00631 pcm.constraint_region.primitives.resize(1);
00632 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
00633 pcm.constraint_region.primitives[0].dimensions.resize(1);
00634 pcm.constraint_region.primitives[0].dimensions[0] = 0.001;
00635
00636 pcm.header.frame_id = kmodel->getModelFrame();
00637
00638 pcm.constraint_region.primitive_poses.resize(1);
00639 pcm.constraint_region.primitive_poses[0].position.x = 0.55;
00640 pcm.constraint_region.primitive_poses[0].position.y = 0.2;
00641 pcm.constraint_region.primitive_poses[0].position.z = 1.25;
00642 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
00643 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
00644 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
00645 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
00646 pcm.weight = 1.0;
00647
00648 moveit_msgs::OrientationConstraint ocm;
00649
00650 ocm.link_name = "l_wrist_roll_link";
00651 ocm.header.frame_id = kmodel->getModelFrame();
00652 ocm.orientation.x = 0.0;
00653 ocm.orientation.y = 0.0;
00654 ocm.orientation.z = 0.0;
00655 ocm.orientation.w = 1.0;
00656 ocm.absolute_x_axis_tolerance = 0.2;
00657 ocm.absolute_y_axis_tolerance = 0.1;
00658 ocm.absolute_z_axis_tolerance = 0.4;
00659 ocm.weight = 1.0;
00660
00661
00662 moveit_msgs::Constraints c;
00663 c.position_constraints.push_back(pcm);
00664 c.orientation_constraints.push_back(ocm);
00665
00666 constraint_samplers::ConstraintSamplerPtr s = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "left_arm", c);
00667 EXPECT_TRUE(s.get() != NULL);
00668 constraint_samplers::IKConstraintSampler* iks = dynamic_cast<constraint_samplers::IKConstraintSampler*>(s.get());
00669 ASSERT_TRUE(iks);
00670 ASSERT_TRUE(iks->getPositionConstraint());
00671 ASSERT_TRUE(iks->getOrientationConstraint());
00672
00673 static const int NT = 100;
00674 int succ = 0;
00675 for (int t = 0 ; t < NT ; ++t)
00676 {
00677 EXPECT_TRUE(s->sample(ks.getJointStateGroup("left_arm"), ks, 100));
00678 EXPECT_TRUE(iks->getPositionConstraint()->decide(ks).satisfied);
00679 EXPECT_TRUE(iks->getOrientationConstraint()->decide(ks).satisfied);
00680 if (s->sample(ks.getJointStateGroup("left_arm"), ks, 1))
00681 succ++;
00682 }
00683 ROS_INFO("Success rate for IK Constraint Sampler with position & orientation constraints for one arm: %lf", (double)succ / (double)NT);
00684
00685
00686 ocm.absolute_x_axis_tolerance = 0.1;
00687
00688 c.orientation_constraints.push_back(ocm);
00689
00690 s = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "left_arm", c);
00691 EXPECT_TRUE(s.get() != NULL);
00692
00693 iks = dynamic_cast<constraint_samplers::IKConstraintSampler*>(s.get());
00694 ASSERT_TRUE(iks);
00695 ASSERT_TRUE(iks->getOrientationConstraint());
00696 EXPECT_NEAR(iks->getOrientationConstraint()->getXAxisTolerance(),.1, .0001);
00697 }
00698
00699 TEST_F(LoadPlanningModelsPr2, JointVersusPoseConstraintSamplerManager)
00700 {
00701 robot_state::RobotState ks(kmodel);
00702 ks.setToDefaultValues();
00703
00704 moveit_msgs::Constraints con;
00705 con.joint_constraints.resize(1);
00706
00707 con.joint_constraints[0].joint_name = "l_shoulder_pan_joint";
00708 con.joint_constraints[0].position = 0.54;
00709 con.joint_constraints[0].tolerance_above = 0.01;
00710 con.joint_constraints[0].tolerance_below = 0.01;
00711 con.joint_constraints[0].weight = 1.0;
00712
00713 constraint_samplers::ConstraintSamplerPtr s = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "right_arm", con);
00714 EXPECT_FALSE(s);
00715 s = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "left_arm", con);
00716 EXPECT_TRUE(s);
00717
00718 con.joint_constraints.resize(7);
00719
00720 con.joint_constraints[1].joint_name = "l_shoulder_lift_joint";
00721 con.joint_constraints[1].position = 0.54;
00722 con.joint_constraints[1].tolerance_above = 0.01;
00723 con.joint_constraints[1].tolerance_below = 0.01;
00724 con.joint_constraints[1].weight = 1.0;
00725
00726 con.joint_constraints[2].joint_name = "l_upper_arm_roll_joint";
00727 con.joint_constraints[2].position = 0.54;
00728 con.joint_constraints[2].tolerance_above = 0.01;
00729 con.joint_constraints[2].tolerance_below = 0.01;
00730 con.joint_constraints[2].weight = 1.0;
00731
00732 con.joint_constraints[3].joint_name = "l_elbow_flex_joint";
00733 con.joint_constraints[3].position = -0.54;
00734 con.joint_constraints[3].tolerance_above = 0.01;
00735 con.joint_constraints[3].tolerance_below = 0.01;
00736 con.joint_constraints[3].weight = 1.0;
00737
00738 con.joint_constraints[4].joint_name = "l_forearm_roll_joint";
00739 con.joint_constraints[4].position = 0.54;
00740 con.joint_constraints[4].tolerance_above = 0.01;
00741 con.joint_constraints[4].tolerance_below = 0.01;
00742 con.joint_constraints[4].weight = 1.0;
00743
00744 con.joint_constraints[5].joint_name = "l_wrist_flex_joint";
00745 con.joint_constraints[5].position = -0.54;
00746 con.joint_constraints[5].tolerance_above = 0.05;
00747 con.joint_constraints[5].tolerance_below = 0.05;
00748 con.joint_constraints[5].weight = 1.0;
00749
00750
00751 con.joint_constraints[6].joint_name = "l_wrist_flex_joint";
00752 con.joint_constraints[6].position = -0.56;
00753 con.joint_constraints[6].tolerance_above = 0.01;
00754 con.joint_constraints[6].tolerance_below = 0.01;
00755 con.joint_constraints[6].weight = 1.0;
00756
00757 s = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "left_arm", con);
00758 EXPECT_TRUE(s);
00759
00760 con.position_constraints.resize(1);
00761
00762
00763 con.position_constraints[0].link_name = "r_wrist_roll_link";
00764 con.position_constraints[0].target_point_offset.x = 0;
00765 con.position_constraints[0].target_point_offset.y = 0;
00766 con.position_constraints[0].target_point_offset.z = 0;
00767 con.position_constraints[0].constraint_region.primitives.resize(1);
00768 con.position_constraints[0].constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
00769 con.position_constraints[0].constraint_region.primitives[0].dimensions.resize(1);
00770 con.position_constraints[0].constraint_region.primitives[0].dimensions[0] = 0.001;
00771
00772 con.position_constraints[0].header.frame_id = kmodel->getModelFrame();
00773
00774 con.position_constraints[0].constraint_region.primitive_poses.resize(1);
00775 con.position_constraints[0].constraint_region.primitive_poses[0].position.x = 0.55;
00776 con.position_constraints[0].constraint_region.primitive_poses[0].position.y = 0.2;
00777 con.position_constraints[0].constraint_region.primitive_poses[0].position.z = 1.25;
00778 con.position_constraints[0].constraint_region.primitive_poses[0].orientation.x = 0.0;
00779 con.position_constraints[0].constraint_region.primitive_poses[0].orientation.y = 0.0;
00780 con.position_constraints[0].constraint_region.primitive_poses[0].orientation.z = 0.0;
00781 con.position_constraints[0].constraint_region.primitive_poses[0].orientation.w = 1.0;
00782 con.position_constraints[0].weight = 1.0;
00783
00784
00785 s = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "left_arm", con);
00786 EXPECT_TRUE(s);
00787 constraint_samplers::JointConstraintSampler* jcs = dynamic_cast<constraint_samplers::JointConstraintSampler*>(s.get());
00788 EXPECT_TRUE(jcs);
00789
00790 con.position_constraints[0].link_name = "l_wrist_roll_link";
00791 s = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "left_arm", con);
00792 EXPECT_TRUE(s);
00793 jcs = dynamic_cast<constraint_samplers::JointConstraintSampler*>(s.get());
00794 EXPECT_FALSE(jcs);
00795 constraint_samplers::IKConstraintSampler* iks = dynamic_cast<constraint_samplers::IKConstraintSampler*>(s.get());
00796 EXPECT_FALSE(iks);
00797
00798
00799 constraint_samplers::UnionConstraintSampler* ucs = dynamic_cast<constraint_samplers::UnionConstraintSampler*>(s.get());
00800 EXPECT_TRUE(ucs);
00801
00802 con.orientation_constraints.resize(1);
00803
00804
00805 con.orientation_constraints[0].link_name = "r_wrist_roll_link";
00806 con.orientation_constraints[0].header.frame_id = kmodel->getModelFrame();
00807 con.orientation_constraints[0].orientation.x = 0.0;
00808 con.orientation_constraints[0].orientation.y = 0.0;
00809 con.orientation_constraints[0].orientation.z = 0.0;
00810 con.orientation_constraints[0].orientation.w = 1.0;
00811 con.orientation_constraints[0].absolute_x_axis_tolerance = 0.2;
00812 con.orientation_constraints[0].absolute_y_axis_tolerance = 0.1;
00813 con.orientation_constraints[0].absolute_z_axis_tolerance = 0.4;
00814 con.orientation_constraints[0].weight = 1.0;
00815
00816
00817 s = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "left_arm", con);
00818 EXPECT_TRUE(s);
00819 ucs = dynamic_cast<constraint_samplers::UnionConstraintSampler*>(s.get());
00820 ASSERT_TRUE(ucs);
00821 jcs = dynamic_cast<constraint_samplers::JointConstraintSampler*>(ucs->getSamplers()[0].get());
00822 iks = dynamic_cast<constraint_samplers::IKConstraintSampler*>(ucs->getSamplers()[1].get());
00823
00824 ASSERT_TRUE(iks);
00825 ASSERT_TRUE(jcs);
00826 EXPECT_TRUE(iks->getPositionConstraint());
00827 EXPECT_FALSE(iks->getOrientationConstraint());
00828
00829 con.orientation_constraints[0].link_name = "l_wrist_roll_link";
00830
00831
00832 s = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "left_arm", con);
00833 EXPECT_TRUE(s);
00834 ucs = dynamic_cast<constraint_samplers::UnionConstraintSampler*>(s.get());
00835 iks = dynamic_cast<constraint_samplers::IKConstraintSampler*>(ucs->getSamplers()[1].get());
00836 ASSERT_TRUE(iks);
00837 EXPECT_TRUE(iks->getPositionConstraint());
00838 EXPECT_TRUE(iks->getOrientationConstraint());
00839
00840
00841 con.position_constraints[0].link_name = "r_wrist_roll_link";
00842 s = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "left_arm", con);
00843 ASSERT_TRUE(s);
00844 ucs = dynamic_cast<constraint_samplers::UnionConstraintSampler*>(s.get());
00845 iks = dynamic_cast<constraint_samplers::IKConstraintSampler*>(ucs->getSamplers()[1].get());
00846 ASSERT_TRUE(iks);
00847 EXPECT_FALSE(iks->getPositionConstraint());
00848 EXPECT_TRUE(iks->getOrientationConstraint());
00849
00850
00851 con.joint_constraints.resize(8);
00852 con.joint_constraints[7].joint_name = "l_wrist_roll_joint";
00853 con.joint_constraints[7].position = 0.54;
00854 con.joint_constraints[7].tolerance_above = 0.01;
00855 con.joint_constraints[7].tolerance_below = 0.01;
00856 con.joint_constraints[7].weight = 1.0;
00857
00858 s = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "left_arm", con);
00859 EXPECT_TRUE(s);
00860 jcs = dynamic_cast<constraint_samplers::JointConstraintSampler*>(s.get());
00861 ASSERT_TRUE(jcs);
00862 }
00863
00864 TEST_F(LoadPlanningModelsPr2, MixedJointAndIkSamplerManager)
00865 {
00866 robot_state::RobotState ks(kmodel);
00867 ks.setToDefaultValues();
00868 robot_state::Transforms &tf = ps->getTransformsNonConst();
00869
00870 std::map<std::string, double> state_values;
00871 ks.getStateValues(state_values);
00872
00873 moveit_msgs::Constraints con;
00874 con.joint_constraints.resize(1);
00875
00876 con.joint_constraints[0].joint_name = "torso_lift_joint";
00877 con.joint_constraints[0].position = state_values["torso_lift_joint"];
00878 con.joint_constraints[0].tolerance_above = 0.01;
00879 con.joint_constraints[0].tolerance_below = 0.01;
00880 con.joint_constraints[0].weight = 1.0;
00881
00882 kinematic_constraints::JointConstraint jc(kmodel);
00883 EXPECT_TRUE(jc.configure(con.joint_constraints[0]));
00884
00885 con.position_constraints.resize(1);
00886
00887 con.position_constraints[0].link_name = "l_wrist_roll_link";
00888 con.position_constraints[0].target_point_offset.x = 0;
00889 con.position_constraints[0].target_point_offset.y = 0;
00890 con.position_constraints[0].target_point_offset.z = 0;
00891 con.position_constraints[0].constraint_region.primitives.resize(1);
00892 con.position_constraints[0].constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
00893 con.position_constraints[0].constraint_region.primitives[0].dimensions.resize(1);
00894 con.position_constraints[0].constraint_region.primitives[0].dimensions[0] = 0.001;
00895
00896 con.position_constraints[0].constraint_region.primitive_poses.resize(1);
00897 con.position_constraints[0].constraint_region.primitive_poses[0].position.x = 0.55;
00898 con.position_constraints[0].constraint_region.primitive_poses[0].position.y = 0.2;
00899 con.position_constraints[0].constraint_region.primitive_poses[0].position.z = 1.25;
00900 con.position_constraints[0].constraint_region.primitive_poses[0].orientation.x = 0.0;
00901 con.position_constraints[0].constraint_region.primitive_poses[0].orientation.y = 0.0;
00902 con.position_constraints[0].constraint_region.primitive_poses[0].orientation.z = 0.0;
00903 con.position_constraints[0].constraint_region.primitive_poses[0].orientation.w = 1.0;
00904 con.position_constraints[0].weight = 1.0;
00905
00906 con.position_constraints[0].header.frame_id = kmodel->getModelFrame();
00907
00908 con.orientation_constraints.resize(1);
00909 con.orientation_constraints[0].link_name = "l_wrist_roll_link";
00910 con.orientation_constraints[0].header.frame_id = kmodel->getModelFrame();
00911 con.orientation_constraints[0].orientation.x = 0.0;
00912 con.orientation_constraints[0].orientation.y = 0.0;
00913 con.orientation_constraints[0].orientation.z = 0.0;
00914 con.orientation_constraints[0].orientation.w = 1.0;
00915 con.orientation_constraints[0].absolute_x_axis_tolerance = 0.2;
00916 con.orientation_constraints[0].absolute_y_axis_tolerance = 0.1;
00917 con.orientation_constraints[0].absolute_z_axis_tolerance = 0.4;
00918 con.orientation_constraints[0].weight = 1.0;
00919
00920 constraint_samplers::ConstraintSamplerPtr s = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "arms_and_torso", con);
00921
00922 constraint_samplers::UnionConstraintSampler* ucs = dynamic_cast<constraint_samplers::UnionConstraintSampler*>(s.get());
00923 ASSERT_TRUE(ucs);
00924
00925 constraint_samplers::IKConstraintSampler* ikcs_test = dynamic_cast<constraint_samplers::IKConstraintSampler*>(ucs->getSamplers()[1].get());
00926
00927 ASSERT_TRUE(ikcs_test);
00928
00929 for (int t = 0 ; t < 1; ++t)
00930 {
00931 EXPECT_TRUE(s->sample(ks.getJointStateGroup("arms_and_torso"), ks, 1));
00932 EXPECT_TRUE(jc.decide(ks).satisfied);
00933 EXPECT_TRUE(ikcs_test->getPositionConstraint()->decide(ks).satisfied);
00934 EXPECT_TRUE(ikcs_test->getOrientationConstraint()->decide(ks).satisfied);
00935 }
00936 }
00937
00938 TEST_F(LoadPlanningModelsPr2, SubgroupJointConstraintsSamplerManager)
00939 {
00940 robot_state::RobotState ks(kmodel);
00941 ks.setToDefaultValues();
00942 robot_state::Transforms &tf = ps->getTransformsNonConst();
00943
00944 kinematic_constraints::JointConstraint jc1(kmodel);
00945 moveit_msgs::JointConstraint jcm1;
00946 jcm1.joint_name = "head_pan_joint";
00947 jcm1.position = 0.42;
00948 jcm1.tolerance_above = 0.01;
00949 jcm1.tolerance_below = 0.05;
00950 jcm1.weight = 1.0;
00951 EXPECT_TRUE(jc1.configure(jcm1));
00952
00953 kinematic_constraints::JointConstraint jc2(kmodel);
00954 moveit_msgs::JointConstraint jcm2;
00955 jcm2.joint_name = "l_shoulder_pan_joint";
00956 jcm2.position = 0.9;
00957 jcm2.tolerance_above = 0.1;
00958 jcm2.tolerance_below = 0.05;
00959 jcm2.weight = 1.0;
00960 EXPECT_TRUE(jc2.configure(jcm2));
00961
00962 kinematic_constraints::JointConstraint jc3(kmodel);
00963 moveit_msgs::JointConstraint jcm3;
00964 jcm3.joint_name = "r_wrist_roll_joint";
00965 jcm3.position = 0.7;
00966 jcm3.tolerance_above = 0.14;
00967 jcm3.tolerance_below = 0.005;
00968 jcm3.weight = 1.0;
00969 EXPECT_TRUE(jc3.configure(jcm3));
00970
00971 kinematic_constraints::JointConstraint jc4(kmodel);
00972 moveit_msgs::JointConstraint jcm4;
00973 jcm4.joint_name = "torso_lift_joint";
00974 jcm4.position = 0.2;
00975 jcm4.tolerance_above = 0.09;
00976 jcm4.tolerance_below = 0.01;
00977 jcm4.weight = 1.0;
00978 EXPECT_TRUE(jc4.configure(jcm4));
00979
00980 std::vector<kinematic_constraints::JointConstraint> js;
00981 js.push_back(jc1);
00982 js.push_back(jc2);
00983 js.push_back(jc3);
00984 js.push_back(jc4);
00985
00986 constraint_samplers::JointConstraintSampler jcs(ps, "arms");
00987 jcs.configure(js);
00988 EXPECT_EQ(jcs.getConstrainedJointCount(), 2);
00989 EXPECT_EQ(jcs.getUnconstrainedJointCount(), 12);
00990
00991 for (int t = 0 ; t < 100 ; ++t)
00992 {
00993 EXPECT_TRUE(jcs.sample(ks.getJointStateGroup("arms"), ks, 1));
00994 EXPECT_TRUE(jc2.decide(ks).satisfied);
00995 EXPECT_TRUE(jc3.decide(ks).satisfied);
00996 }
00997
00998
00999 moveit_msgs::Constraints c;
01000
01001
01002 constraint_samplers::ConstraintSamplerPtr s0 = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "arms", c);
01003 EXPECT_TRUE(s0.get() == NULL);
01004
01005
01006 c.joint_constraints.push_back(jcm1);
01007 c.joint_constraints.push_back(jcm2);
01008 c.joint_constraints.push_back(jcm3);
01009 c.joint_constraints.push_back(jcm4);
01010
01011 constraint_samplers::ConstraintSamplerPtr s = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "arms", c);
01012 EXPECT_TRUE(s.get() != NULL);
01013
01014
01015 for (int t = 0 ; t < 1000 ; ++t)
01016 {
01017 EXPECT_TRUE(s->sample(ks.getJointStateGroup("arms"), ks, 1));
01018 EXPECT_TRUE(jc2.decide(ks).satisfied);
01019 EXPECT_TRUE(jc3.decide(ks).satisfied);
01020 }
01021 }
01022
01023 TEST_F(LoadPlanningModelsPr2, SubgroupPoseConstraintsSampler)
01024 {
01025 moveit_msgs::Constraints c;
01026
01027 moveit_msgs::PositionConstraint pcm;
01028 pcm.link_name = "l_wrist_roll_link";
01029 pcm.target_point_offset.x = 0;
01030 pcm.target_point_offset.y = 0;
01031 pcm.target_point_offset.z = 0;
01032
01033 pcm.constraint_region.primitives.resize(1);
01034 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
01035 pcm.constraint_region.primitives[0].dimensions.resize(1);
01036 pcm.constraint_region.primitives[0].dimensions[0] = 0.001;
01037
01038 pcm.header.frame_id = kmodel->getModelFrame();
01039
01040 pcm.constraint_region.primitive_poses.resize(1);
01041 pcm.constraint_region.primitive_poses[0].position.x = 0.55;
01042 pcm.constraint_region.primitive_poses[0].position.y = 0.2;
01043 pcm.constraint_region.primitive_poses[0].position.z = 1.25;
01044 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
01045 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
01046 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
01047 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
01048 pcm.weight = 1.0;
01049 c.position_constraints.push_back(pcm);
01050
01051 moveit_msgs::OrientationConstraint ocm;
01052 ocm.link_name = "l_wrist_roll_link";
01053 ocm.header.frame_id = kmodel->getModelFrame();
01054 ocm.orientation.x = 0.0;
01055 ocm.orientation.y = 0.0;
01056 ocm.orientation.z = 0.0;
01057 ocm.orientation.w = 1.0;
01058 ocm.absolute_x_axis_tolerance = 0.2;
01059 ocm.absolute_y_axis_tolerance = 0.1;
01060 ocm.absolute_z_axis_tolerance = 0.4;
01061 ocm.weight = 1.0;
01062 c.orientation_constraints.push_back(ocm);
01063
01064 ocm.link_name = "r_wrist_roll_link";
01065 ocm.header.frame_id = kmodel->getModelFrame();
01066 ocm.orientation.x = 0.0;
01067 ocm.orientation.y = 0.0;
01068 ocm.orientation.z = 0.0;
01069 ocm.orientation.w = 1.0;
01070 ocm.absolute_x_axis_tolerance = 0.01;
01071 ocm.absolute_y_axis_tolerance = 0.01;
01072 ocm.absolute_z_axis_tolerance = 0.01;
01073 ocm.weight = 1.0;
01074 c.orientation_constraints.push_back(ocm);
01075
01076 robot_state::Transforms &tf = ps->getTransformsNonConst();
01077 constraint_samplers::ConstraintSamplerPtr s = constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(ps, "arms", c);
01078 EXPECT_TRUE(s);
01079 constraint_samplers::UnionConstraintSampler* ucs = dynamic_cast<constraint_samplers::UnionConstraintSampler*>(s.get());
01080 EXPECT_TRUE(ucs);
01081
01082 kinematic_constraints::KinematicConstraintSet kset(kmodel);
01083 kset.add(c, tf);
01084
01085 robot_state::RobotState ks(kmodel);
01086 ks.setToDefaultValues();
01087 static const int NT = 100;
01088 int succ = 0;
01089 for (int t = 0 ; t < NT ; ++t)
01090 {
01091 EXPECT_TRUE(s->sample(ks.getJointStateGroup("arms"), ks, 1000));
01092 EXPECT_TRUE(kset.decide(ks).satisfied);
01093 if (s->sample(ks.getJointStateGroup("arms"), ks, 1))
01094 succ++;
01095 }
01096 logInform("Success rate for IK Constraint Sampler with position & orientation constraints for both arms: %lf", (double)succ / (double)NT);
01097 }
01098
01099 int main(int argc, char **argv)
01100 {
01101 testing::InitGoogleTest(&argc, argv);
01102 ros::Time::init();
01103 return RUN_ALL_TESTS();
01104 }