38 #include <gtest/gtest.h>
39 #include <urdf_parser/urdf_parser.h>
43 #include <boost/math/constants/constants.hpp>
68 moveit_msgs::JointConstraint jcm;
69 jcm.joint_name =
"head_pan_joint";
71 jcm.tolerance_above = 0.1;
72 jcm.tolerance_below = 0.05;
88 robot_state.setJointPositions(jcm.joint_name, &jval);
95 robot_state.setJointPositions(jcm.joint_name, &jval);
100 jval = 0.35 - std::numeric_limits<double>::epsilon();
102 robot_state.setJointPositions(jcm.joint_name, &jval);
106 jval = 0.35 - 3 * std::numeric_limits<double>::epsilon();
107 robot_state.setJointPositions(jcm.joint_name, &jval);
111 jcm.tolerance_below = -0.05;
114 jcm.tolerance_below = 0.05;
119 robot_state.setJointPositions(jcm.joint_name, &jval);
124 robot_state.setJointPositions(jcm.joint_name, &jval);
129 robot_state.setJointPositions(jcm.joint_name, &jval);
134 robot_state.setJointPositions(jcm.joint_name, &jval);
144 jcm.joint_name =
"head_tilt_joint";
149 jcm.joint_name =
"head_pan_joint";
165 jcm.joint_name =
"base_footprint_joint";
169 jcm.joint_name =
"head_pan_joint";
184 moveit_msgs::JointConstraint jcm;
186 jcm.joint_name =
"l_wrist_roll_joint";
188 jcm.tolerance_above = 0.04;
189 jcm.tolerance_below = 0.02;
194 std::map<std::string, double> jvals;
200 jvals[jcm.joint_name] = .03;
206 jvals[jcm.joint_name] = .05;
212 jvals[jcm.joint_name] = -.01;
217 jvals[jcm.joint_name] = -.03;
226 jvals[jcm.joint_name] = 3.17;
233 jvals[jcm.joint_name] = -3.14;
240 jvals[jcm.joint_name] = 3.19;
246 jvals[jcm.joint_name] = -3.11;
251 jvals[jcm.joint_name] = -3.09;
257 jvals[jcm.joint_name] = 3.13;
262 jvals[jcm.joint_name] = 3.11;
267 jcm.position = -3.14;
271 jvals[jcm.joint_name] = -3.11;
276 jvals[jcm.joint_name] = -3.09;
281 jvals[jcm.joint_name] = 3.13;
286 jvals[jcm.joint_name] = 3.12;
295 jvals[jcm.joint_name] = 0.0;
300 moveit_msgs::JointConstraint jcm2 = jcm;
301 jcm2.position = -6.28;
313 moveit_msgs::JointConstraint jcm;
314 jcm.joint_name =
"world_joint";
316 jcm.tolerance_above = 0.1;
317 jcm.tolerance_below = 0.05;
324 jcm.joint_name =
"world_joint/x";
327 std::map<std::string, double> jvals;
328 jvals[jcm.joint_name] = 3.2;
333 jvals[jcm.joint_name] = 3.25;
338 jvals[jcm.joint_name] = -3.14;
344 jcm.joint_name =
"world_joint/theta";
347 jvals[jcm.joint_name] = -3.14;
352 jvals[jcm.joint_name] = 3.25;
365 moveit_msgs::PositionConstraint pcm;
370 pcm.link_name =
"l_wrist_roll_link";
371 pcm.target_point_offset.x = 0;
372 pcm.target_point_offset.y = 0;
373 pcm.target_point_offset.z = 0;
374 pcm.constraint_region.primitives.resize(1);
375 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
380 pcm.constraint_region.primitives[0].dimensions.resize(1);
381 pcm.constraint_region.primitives[0].dimensions[0] = 0.2;
386 pcm.constraint_region.primitive_poses.resize(1);
387 pcm.constraint_region.primitive_poses[0].position.x = 0.55;
388 pcm.constraint_region.primitive_poses[0].position.y = 0.2;
389 pcm.constraint_region.primitive_poses[0].position.z = 1.25;
390 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
391 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
392 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
393 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
399 pcm.header.frame_id = robot_model_->getModelFrame();
405 std::map<std::string, double> jvals;
406 jvals[
"torso_lift_joint"] = 0.4;
413 pcm.target_point_offset.x = 0;
414 pcm.target_point_offset.y = 0;
415 pcm.target_point_offset.z = .15;
425 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
426 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
427 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
428 pcm.constraint_region.primitive_poses[0].orientation.w = 0.0;
442 moveit_msgs::PositionConstraint pcm;
444 pcm.link_name =
"l_wrist_roll_link";
445 pcm.target_point_offset.x = 0;
446 pcm.target_point_offset.y = 0;
447 pcm.target_point_offset.z = 0;
449 pcm.constraint_region.primitives.resize(1);
450 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
451 pcm.constraint_region.primitives[0].dimensions.resize(1);
452 pcm.constraint_region.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = 0.38 * 2.0;
454 pcm.header.frame_id =
"r_wrist_roll_link";
456 pcm.constraint_region.primitive_poses.resize(1);
457 pcm.constraint_region.primitive_poses[0].position.x = 0.0;
458 pcm.constraint_region.primitive_poses[0].position.y = 0.6;
459 pcm.constraint_region.primitive_poses[0].position.z = 0.0;
460 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
461 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
462 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
463 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
472 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
473 pcm.constraint_region.primitives[0].dimensions.resize(3);
474 pcm.constraint_region.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = 0.1;
475 pcm.constraint_region.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = 0.1;
476 pcm.constraint_region.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = 0.1;
479 std::map<std::string, double> jvals;
480 jvals[
"l_shoulder_pan_joint"] = 0.4;
486 jvals[
"l_shoulder_pan_joint"] = -0.4;
492 pcm.constraint_region.primitive_poses.resize(2);
493 pcm.constraint_region.primitive_poses[1].position.x = 0.0;
494 pcm.constraint_region.primitive_poses[1].position.y = 0.1;
495 pcm.constraint_region.primitive_poses[1].position.z = 0.0;
496 pcm.constraint_region.primitive_poses[1].orientation.x = 0.0;
497 pcm.constraint_region.primitive_poses[1].orientation.y = 0.0;
498 pcm.constraint_region.primitive_poses[1].orientation.z = 0.0;
499 pcm.constraint_region.primitive_poses[1].orientation.w = 1.0;
501 pcm.constraint_region.primitives.resize(2);
502 pcm.constraint_region.primitives[1].type = shape_msgs::SolidPrimitive::BOX;
503 pcm.constraint_region.primitives[1].dimensions.resize(3);
504 pcm.constraint_region.primitives[1].dimensions[shape_msgs::SolidPrimitive::BOX_X] = 0.1;
505 pcm.constraint_region.primitives[1].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = 0.1;
506 pcm.constraint_region.primitives[1].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = 0.1;
519 moveit_msgs::PositionConstraint pcm;
521 pcm.link_name =
"l_wrist_roll_link";
522 pcm.target_point_offset.x = 0;
523 pcm.target_point_offset.y = 0;
524 pcm.target_point_offset.z = 0;
526 pcm.constraint_region.primitives.resize(2);
527 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
528 pcm.constraint_region.primitives[0].dimensions.resize(1);
529 pcm.constraint_region.primitives[0].dimensions[0] = 0.38 * 2.0;
530 pcm.constraint_region.primitives[1].type = shape_msgs::SolidPrimitive::BOX;
531 pcm.constraint_region.primitives[1].dimensions.resize(3);
532 pcm.constraint_region.primitives[1].dimensions[shape_msgs::SolidPrimitive::BOX_X] = 2.0;
533 pcm.constraint_region.primitives[1].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = 2.0;
534 pcm.constraint_region.primitives[1].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = 2.0;
536 pcm.header.frame_id =
"r_wrist_roll_link";
537 pcm.constraint_region.primitive_poses.resize(2);
538 pcm.constraint_region.primitive_poses[0].position.x = 0.0;
539 pcm.constraint_region.primitive_poses[0].position.y = 0.6;
540 pcm.constraint_region.primitive_poses[0].position.z = 0.0;
541 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
542 pcm.constraint_region.primitive_poses[1].position.x = 2.0;
543 pcm.constraint_region.primitive_poses[1].position.y = 0.0;
544 pcm.constraint_region.primitive_poses[1].position.z = 0.0;
545 pcm.constraint_region.primitive_poses[1].orientation.w = 1.0;
555 moveit_msgs::PositionConstraint pcm2 = pcm;
556 pcm2.constraint_region.primitives[0] = pcm.constraint_region.primitives[1];
557 pcm2.constraint_region.primitives[1] = pcm.constraint_region.primitives[0];
559 pcm2.constraint_region.primitive_poses[0] = pcm.constraint_region.primitive_poses[1];
560 pcm2.constraint_region.primitive_poses[1] = pcm.constraint_region.primitive_poses[0];
567 pcm2.constraint_region.primitive_poses[0].position.z = .01;
575 pcm2.constraint_region.primitive_poses[0].position.z = 0.0;
576 pcm2.constraint_region.primitives.resize(3);
577 pcm2.constraint_region.primitive_poses.resize(3);
578 pcm2.constraint_region.primitives[2] = pcm2.constraint_region.primitives[0];
579 pcm2.constraint_region.primitive_poses[2] = pcm2.constraint_region.primitive_poses[0];
585 pcm2.constraint_region.primitives[2].dimensions[0] = 3.0;
591 pcm2.constraint_region.primitives[2].dimensions[0] = pcm2.constraint_region.primitives[0].dimensions[0];
592 pcm2.constraint_region.primitives[2].type = shape_msgs::SolidPrimitive::SPHERE;
606 moveit_msgs::OrientationConstraint ocm;
610 ocm.link_name =
"r_wrist_roll_link";
615 ocm.header.frame_id = robot_model_->getModelFrame();
616 ocm.orientation.x = 0.0;
617 ocm.orientation.y = 0.0;
618 ocm.orientation.z = 0.0;
619 ocm.orientation.w = 1.0;
620 ocm.absolute_x_axis_tolerance = 0.1;
621 ocm.absolute_y_axis_tolerance = 0.1;
622 ocm.absolute_z_axis_tolerance = 0.1;
630 ocm.header.frame_id = ocm.link_name;
641 ocm.orientation = p.orientation;
642 ocm.header.frame_id = robot_model_->getModelFrame();
646 std::map<std::string, double> jvals;
647 jvals[
"r_wrist_roll_joint"] = .05;
652 jvals[
"r_wrist_roll_joint"] = .11;
658 jvals[
"r_wrist_roll_joint"] = boost::math::constants::pi<double>();
672 moveit_msgs::VisibilityConstraint vcm;
676 vcm.sensor_pose.header.frame_id =
"base_footprint";
677 vcm.sensor_pose.pose.position.z = -1.0;
678 vcm.sensor_pose.pose.orientation.y = 1.0;
680 vcm.target_pose.header.frame_id =
"base_footprint";
681 vcm.target_pose.pose.position.z = -2.0;
682 vcm.target_pose.pose.orientation.y = 0.0;
683 vcm.target_pose.pose.orientation.w = 1.0;
685 vcm.target_radius = .2;
687 vcm.max_view_angle = 0.0;
688 vcm.max_range_angle = 0.0;
689 vcm.sensor_view_direction = moveit_msgs::VisibilityConstraint::SENSOR_Z;
696 vcm.max_view_angle = .1;
703 vcm.target_pose.pose.orientation.y = 0.03;
704 vcm.target_pose.pose.orientation.w = sqrt(1 - pow(vcm.target_pose.pose.orientation.y, 2));
709 vcm.target_pose.pose.orientation.y = 0.06;
710 vcm.target_pose.pose.orientation.w = sqrt(1 - pow(vcm.target_pose.pose.orientation.y, 2));
723 moveit_msgs::VisibilityConstraint vcm;
725 vcm.sensor_pose.header.frame_id =
"narrow_stereo_optical_frame";
726 vcm.sensor_pose.pose.position.z = 0.05;
727 vcm.sensor_pose.pose.orientation.w = 1.0;
729 vcm.target_pose.header.frame_id =
"l_gripper_r_finger_tip_link";
730 vcm.target_pose.pose.position.z = 0.03;
731 vcm.target_pose.pose.orientation.w = 1.0;
734 vcm.max_view_angle = 0.0;
735 vcm.max_range_angle = 0.0;
736 vcm.sensor_view_direction = moveit_msgs::VisibilityConstraint::SENSOR_Z;
743 vcm.target_radius = .05;
748 std::map<std::string, double> state_values;
749 state_values[
"l_shoulder_lift_joint"] = .5;
750 state_values[
"r_shoulder_pan_joint"] = .5;
751 state_values[
"r_elbow_flex_joint"] = -1.4;
757 state_values[
"r_shoulder_pan_joint"] = .4;
763 state_values[
"l_shoulder_lift_joint"] = 0;
764 state_values[
"r_shoulder_pan_joint"] = .5;
765 state_values[
"r_elbow_flex_joint"] = -.6;
771 vcm.sensor_view_direction = moveit_msgs::VisibilityConstraint::SENSOR_X;
777 vcm.target_radius = .01;
778 vcm.target_pose.pose.position.z = 0.00;
779 vcm.target_pose.pose.position.x = 0.035;
784 vcm.target_radius = .05;
798 moveit_msgs::JointConstraint jcm;
799 jcm.joint_name =
"head_pan_joint";
801 jcm.tolerance_above = 0.1;
802 jcm.tolerance_below = 0.05;
806 std::vector<moveit_msgs::JointConstraint> jcv;
814 std::map<std::string, double> jvals;
815 jvals[jcm.joint_name] = 0.41;
825 jcv.back().joint_name =
"head_tilt_joint";
832 jvals[jcv.back().joint_name] = 0.41;
837 jvals[jcv.back().joint_name] = 0.51;
843 jcv.back().joint_name =
"no_joint";
850 jvals[
"head_pan_joint"] = 0.51;
864 moveit_msgs::JointConstraint jcm;
865 jcm.joint_name =
"head_pan_joint";
867 jcm.tolerance_above = 0.1;
868 jcm.tolerance_below = 0.05;
871 moveit_msgs::PositionConstraint pcm;
872 pcm.link_name =
"l_wrist_roll_link";
873 pcm.target_point_offset.x = 0;
874 pcm.target_point_offset.y = 0;
875 pcm.target_point_offset.z = 0;
876 pcm.constraint_region.primitives.resize(1);
877 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
878 pcm.constraint_region.primitives[0].dimensions.resize(1);
879 pcm.constraint_region.primitives[0].dimensions[0] = 0.2;
881 pcm.constraint_region.primitive_poses.resize(1);
882 pcm.constraint_region.primitive_poses[0].position.x = 0.55;
883 pcm.constraint_region.primitive_poses[0].position.y = 0.2;
884 pcm.constraint_region.primitive_poses[0].position.z = 1.25;
885 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
886 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
887 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
888 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
891 pcm.header.frame_id = robot_model_->getModelFrame();
894 std::vector<moveit_msgs::JointConstraint> jcv;
898 std::vector<moveit_msgs::PositionConstraint> pcv;
917 jcm.joint_name =
"head_pan_joint";
919 jcm.tolerance_above = 0.1;
920 jcm.tolerance_below = 0.05;
934 int main(
int argc,
char** argv)
936 testing::InitGoogleTest(&argc, argv);
937 return RUN_ALL_TESTS();