38 #include <gtest/gtest.h> 39 #include <urdf_parser/urdf_parser.h> 42 #include <boost/filesystem/path.hpp> 43 #include <moveit_resources/config.h> 50 boost::filesystem::path res_path(MOVEIT_TEST_RESOURCES_DIR);
54 std::fstream xml_file((res_path /
"pr2_description/urdf/robot.xml").
string().c_str(), std::fstream::in);
55 if (xml_file.is_open())
57 while (xml_file.good())
60 std::getline(xml_file, line);
61 xml_string += (line +
"\n");
68 FAIL() <<
"Failed to find robot.xml";
81 robot_model::RobotModelPtr
kmodel;
91 moveit_msgs::JointConstraint jcm;
92 jcm.joint_name =
"head_pan_joint";
94 jcm.tolerance_above = 0.1;
95 jcm.tolerance_below = 0.05;
99 EXPECT_NEAR(jc.getConstraintWeight(), 1.0, std::numeric_limits<double>::epsilon());
123 jval = 0.35 - std::numeric_limits<double>::epsilon();
129 jval = 0.35 - 3 * std::numeric_limits<double>::epsilon();
134 jcm.tolerance_below = -0.05;
137 jcm.tolerance_below = 0.05;
167 jcm.joint_name =
"head_tilt_joint";
172 jcm.joint_name =
"head_pan_joint";
188 jcm.joint_name =
"base_footprint_joint";
192 jcm.joint_name =
"head_pan_joint";
207 moveit_msgs::JointConstraint jcm;
209 jcm.joint_name =
"l_wrist_roll_joint";
211 jcm.tolerance_above = 0.04;
212 jcm.tolerance_below = 0.02;
217 std::map<std::string, double> jvals;
223 jvals[jcm.joint_name] = .03;
229 jvals[jcm.joint_name] = .05;
235 jvals[jcm.joint_name] = -.01;
240 jvals[jcm.joint_name] = -.03;
249 jvals[jcm.joint_name] = 3.17;
256 jvals[jcm.joint_name] = -3.14;
263 jvals[jcm.joint_name] = 3.19;
269 jvals[jcm.joint_name] = -3.11;
274 jvals[jcm.joint_name] = -3.09;
280 jvals[jcm.joint_name] = 3.13;
285 jvals[jcm.joint_name] = 3.11;
290 jcm.position = -3.14;
294 jvals[jcm.joint_name] = -3.11;
299 jvals[jcm.joint_name] = -3.09;
304 jvals[jcm.joint_name] = 3.13;
309 jvals[jcm.joint_name] = 3.12;
318 jvals[jcm.joint_name] = 0.0;
323 moveit_msgs::JointConstraint jcm2 = jcm;
324 jcm2.position = -6.28;
336 moveit_msgs::JointConstraint jcm;
337 jcm.joint_name =
"world_joint";
339 jcm.tolerance_above = 0.1;
340 jcm.tolerance_below = 0.05;
347 jcm.joint_name =
"world_joint/x";
350 std::map<std::string, double> jvals;
351 jvals[jcm.joint_name] = 3.2;
356 jvals[jcm.joint_name] = 3.25;
361 jvals[jcm.joint_name] = -3.14;
367 jcm.joint_name =
"world_joint/theta";
370 jvals[jcm.joint_name] = -3.14;
375 jvals[jcm.joint_name] = 3.25;
388 moveit_msgs::PositionConstraint pcm;
393 pcm.link_name =
"l_wrist_roll_link";
394 pcm.target_point_offset.x = 0;
395 pcm.target_point_offset.y = 0;
396 pcm.target_point_offset.z = 0;
397 pcm.constraint_region.primitives.resize(1);
398 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
403 pcm.constraint_region.primitives[0].dimensions.resize(1);
404 pcm.constraint_region.primitives[0].dimensions[0] = 0.2;
409 pcm.constraint_region.primitive_poses.resize(1);
410 pcm.constraint_region.primitive_poses[0].position.x = 0.55;
411 pcm.constraint_region.primitive_poses[0].position.y = 0.2;
412 pcm.constraint_region.primitive_poses[0].position.z = 1.25;
413 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
414 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
415 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
416 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
422 pcm.header.frame_id =
kmodel->getModelFrame();
428 std::map<std::string, double> jvals;
429 jvals[
"torso_lift_joint"] = 0.4;
436 pcm.target_point_offset.x = 0;
437 pcm.target_point_offset.y = 0;
438 pcm.target_point_offset.z = .15;
448 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
449 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
450 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
451 pcm.constraint_region.primitive_poses[0].orientation.w = 0.0;
465 moveit_msgs::PositionConstraint pcm;
467 pcm.link_name =
"l_wrist_roll_link";
468 pcm.target_point_offset.x = 0;
469 pcm.target_point_offset.y = 0;
470 pcm.target_point_offset.z = 0;
472 pcm.constraint_region.primitives.resize(1);
473 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
474 pcm.constraint_region.primitives[0].dimensions.resize(1);
475 pcm.constraint_region.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = 0.38 * 2.0;
477 pcm.header.frame_id =
"r_wrist_roll_link";
479 pcm.constraint_region.primitive_poses.resize(1);
480 pcm.constraint_region.primitive_poses[0].position.x = 0.0;
481 pcm.constraint_region.primitive_poses[0].position.y = 0.6;
482 pcm.constraint_region.primitive_poses[0].position.z = 0.0;
483 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
484 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
485 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
486 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
495 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
496 pcm.constraint_region.primitives[0].dimensions.resize(3);
497 pcm.constraint_region.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = 0.1;
498 pcm.constraint_region.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = 0.1;
499 pcm.constraint_region.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = 0.1;
502 std::map<std::string, double> jvals;
503 jvals[
"l_shoulder_pan_joint"] = 0.4;
509 jvals[
"l_shoulder_pan_joint"] = -0.4;
515 pcm.constraint_region.primitive_poses.resize(2);
516 pcm.constraint_region.primitive_poses[1].position.x = 0.0;
517 pcm.constraint_region.primitive_poses[1].position.y = 0.1;
518 pcm.constraint_region.primitive_poses[1].position.z = 0.0;
519 pcm.constraint_region.primitive_poses[1].orientation.x = 0.0;
520 pcm.constraint_region.primitive_poses[1].orientation.y = 0.0;
521 pcm.constraint_region.primitive_poses[1].orientation.z = 0.0;
522 pcm.constraint_region.primitive_poses[1].orientation.w = 1.0;
524 pcm.constraint_region.primitives.resize(2);
525 pcm.constraint_region.primitives[1].type = shape_msgs::SolidPrimitive::BOX;
526 pcm.constraint_region.primitives[1].dimensions.resize(3);
527 pcm.constraint_region.primitives[1].dimensions[shape_msgs::SolidPrimitive::BOX_X] = 0.1;
528 pcm.constraint_region.primitives[1].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = 0.1;
529 pcm.constraint_region.primitives[1].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = 0.1;
542 moveit_msgs::PositionConstraint pcm;
544 pcm.link_name =
"l_wrist_roll_link";
545 pcm.target_point_offset.x = 0;
546 pcm.target_point_offset.y = 0;
547 pcm.target_point_offset.z = 0;
549 pcm.constraint_region.primitives.resize(2);
550 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
551 pcm.constraint_region.primitives[0].dimensions.resize(1);
552 pcm.constraint_region.primitives[0].dimensions[0] = 0.38 * 2.0;
553 pcm.constraint_region.primitives[1].type = shape_msgs::SolidPrimitive::BOX;
554 pcm.constraint_region.primitives[1].dimensions.resize(3);
555 pcm.constraint_region.primitives[1].dimensions[shape_msgs::SolidPrimitive::BOX_X] = 2.0;
556 pcm.constraint_region.primitives[1].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = 2.0;
557 pcm.constraint_region.primitives[1].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = 2.0;
559 pcm.header.frame_id =
"r_wrist_roll_link";
560 pcm.constraint_region.primitive_poses.resize(2);
561 pcm.constraint_region.primitive_poses[0].position.x = 0.0;
562 pcm.constraint_region.primitive_poses[0].position.y = 0.6;
563 pcm.constraint_region.primitive_poses[0].position.z = 0.0;
564 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
565 pcm.constraint_region.primitive_poses[1].position.x = 2.0;
566 pcm.constraint_region.primitive_poses[1].position.y = 0.0;
567 pcm.constraint_region.primitive_poses[1].position.z = 0.0;
568 pcm.constraint_region.primitive_poses[1].orientation.w = 1.0;
578 moveit_msgs::PositionConstraint pcm2 = pcm;
579 pcm2.constraint_region.primitives[0] = pcm.constraint_region.primitives[1];
580 pcm2.constraint_region.primitives[1] = pcm.constraint_region.primitives[0];
582 pcm2.constraint_region.primitive_poses[0] = pcm.constraint_region.primitive_poses[1];
583 pcm2.constraint_region.primitive_poses[1] = pcm.constraint_region.primitive_poses[0];
590 pcm2.constraint_region.primitive_poses[0].position.z = .01;
598 pcm2.constraint_region.primitive_poses[0].position.z = 0.0;
599 pcm2.constraint_region.primitives.resize(3);
600 pcm2.constraint_region.primitive_poses.resize(3);
601 pcm2.constraint_region.primitives[2] = pcm2.constraint_region.primitives[0];
602 pcm2.constraint_region.primitive_poses[2] = pcm2.constraint_region.primitive_poses[0];
608 pcm2.constraint_region.primitives[2].dimensions[0] = 3.0;
614 pcm2.constraint_region.primitives[2].dimensions[0] = pcm2.constraint_region.primitives[0].dimensions[0];
615 pcm2.constraint_region.primitives[2].type = shape_msgs::SolidPrimitive::SPHERE;
629 moveit_msgs::OrientationConstraint ocm;
633 ocm.link_name =
"r_wrist_roll_link";
638 ocm.header.frame_id =
kmodel->getModelFrame();
639 ocm.orientation.x = 0.0;
640 ocm.orientation.y = 0.0;
641 ocm.orientation.z = 0.0;
642 ocm.orientation.w = 1.0;
643 ocm.absolute_x_axis_tolerance = 0.1;
644 ocm.absolute_y_axis_tolerance = 0.1;
645 ocm.absolute_z_axis_tolerance = 0.1;
653 ocm.header.frame_id = ocm.link_name;
660 ASSERT_TRUE(oc.getLinkModel());
662 geometry_msgs::Pose p;
666 ocm.orientation = p.orientation;
667 ocm.header.frame_id =
kmodel->getModelFrame();
671 std::map<std::string, double> jvals;
672 jvals[
"r_wrist_roll_joint"] = .05;
677 jvals[
"r_wrist_roll_joint"] = .11;
691 moveit_msgs::VisibilityConstraint vcm;
695 vcm.sensor_pose.header.frame_id =
"base_footprint";
696 vcm.sensor_pose.pose.position.z = -1.0;
697 vcm.sensor_pose.pose.orientation.y = 1.0;
699 vcm.target_pose.header.frame_id =
"base_footprint";
700 vcm.target_pose.pose.position.z = -2.0;
701 vcm.target_pose.pose.orientation.y = 0.0;
702 vcm.target_pose.pose.orientation.w = 1.0;
704 vcm.target_radius = .2;
706 vcm.max_view_angle = 0.0;
707 vcm.max_range_angle = 0.0;
708 vcm.sensor_view_direction = moveit_msgs::VisibilityConstraint::SENSOR_Z;
715 vcm.max_view_angle = .1;
722 vcm.target_pose.pose.orientation.y = 0.03;
723 vcm.target_pose.pose.orientation.w = .9995;
728 vcm.target_pose.pose.orientation.y = 0.06;
729 vcm.target_pose.pose.orientation.w = .9981;
742 moveit_msgs::VisibilityConstraint vcm;
744 vcm.sensor_pose.header.frame_id =
"narrow_stereo_optical_frame";
745 vcm.sensor_pose.pose.position.z = 0.05;
746 vcm.sensor_pose.pose.orientation.w = 1.0;
748 vcm.target_pose.header.frame_id =
"l_gripper_r_finger_tip_link";
749 vcm.target_pose.pose.position.z = 0.03;
750 vcm.target_pose.pose.orientation.w = 1.0;
753 vcm.max_view_angle = 0.0;
754 vcm.max_range_angle = 0.0;
755 vcm.sensor_view_direction = moveit_msgs::VisibilityConstraint::SENSOR_Z;
762 vcm.target_radius = .05;
767 std::map<std::string, double> state_values;
768 state_values[
"l_shoulder_lift_joint"] = .5;
769 state_values[
"r_shoulder_pan_joint"] = .5;
770 state_values[
"r_elbow_flex_joint"] = -1.4;
776 state_values[
"r_shoulder_pan_joint"] = .4;
782 state_values[
"l_shoulder_lift_joint"] = 0;
783 state_values[
"r_shoulder_pan_joint"] = .5;
784 state_values[
"r_elbow_flex_joint"] = -.6;
790 vcm.sensor_view_direction = moveit_msgs::VisibilityConstraint::SENSOR_X;
796 vcm.target_radius = .01;
797 vcm.target_pose.pose.position.z = 0.00;
798 vcm.target_pose.pose.position.x = 0.035;
803 vcm.target_radius = .05;
817 moveit_msgs::JointConstraint jcm;
818 jcm.joint_name =
"head_pan_joint";
820 jcm.tolerance_above = 0.1;
821 jcm.tolerance_below = 0.05;
825 std::vector<moveit_msgs::JointConstraint> jcv;
833 std::map<std::string, double> jvals;
834 jvals[jcm.joint_name] = 0.41;
844 jcv.back().joint_name =
"head_tilt_joint";
851 jvals[jcv.back().joint_name] = 0.41;
856 jvals[jcv.back().joint_name] = 0.51;
862 jcv.back().joint_name =
"no_joint";
869 jvals[
"head_pan_joint"] = 0.51;
883 moveit_msgs::JointConstraint jcm;
884 jcm.joint_name =
"head_pan_joint";
886 jcm.tolerance_above = 0.1;
887 jcm.tolerance_below = 0.05;
890 moveit_msgs::PositionConstraint pcm;
891 pcm.link_name =
"l_wrist_roll_link";
892 pcm.target_point_offset.x = 0;
893 pcm.target_point_offset.y = 0;
894 pcm.target_point_offset.z = 0;
895 pcm.constraint_region.primitives.resize(1);
896 pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::SPHERE;
897 pcm.constraint_region.primitives[0].dimensions.resize(1);
898 pcm.constraint_region.primitives[0].dimensions[0] = 0.2;
900 pcm.constraint_region.primitive_poses.resize(1);
901 pcm.constraint_region.primitive_poses[0].position.x = 0.55;
902 pcm.constraint_region.primitive_poses[0].position.y = 0.2;
903 pcm.constraint_region.primitive_poses[0].position.z = 1.25;
904 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
905 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
906 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
907 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
910 pcm.header.frame_id =
kmodel->getModelFrame();
913 std::vector<moveit_msgs::JointConstraint> jcv;
917 std::vector<moveit_msgs::PositionConstraint> pcv;
936 jcm.joint_name =
"head_pan_joint";
938 jcm.tolerance_above = 0.1;
939 jcm.tolerance_below = 0.05;
953 int main(
int argc,
char** argv)
955 testing::InitGoogleTest(&argc, argv);
956 return RUN_ALL_TESTS();
void setJointPositions(const std::string &joint_name, const double *position)
robot_model::RobotModelPtr kmodel
TEST_F(LoadPlanningModelsPr2, JointConstraintsSimple)
Class for constraints on the orientation of a link.
Class for constraints on the visibility relationship between a sensor and a target.
const Eigen::Affine3d & getGlobalLinkTransform(const std::string &link_name)
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
bool configure(const moveit_msgs::PositionConstraint &pc, const robot_state::Transforms &tf)
Configure the constraint based on a moveit_msgs::PositionConstraint.
Class for handling single DOF joint constraints.
A class that contains many different constraints, and can check RobotState *versus the full set...
virtual ConstraintEvaluationResult decide(const robot_state::RobotState &state, bool verbose=false) const
Decide whether the constraint is satisfied in the indicated state.
#define EXPECT_NEAR(a, b, prec)
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state...
bool equal(const KinematicConstraintSet &other, double margin) const
Whether or not another KinematicConstraintSet is equal to this one.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
double distance
The distance evaluation from the constraint or constraints.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
bool add(const moveit_msgs::Constraints &c, const robot_state::Transforms &tf)
Add all known constraints.
bool satisfied
Whether or not the constraint or constraints were satisfied.
#define EXPECT_FALSE(args)
void update(bool force=false)
Update all transforms.
urdf::ModelInterfaceSharedPtr urdf_model
def xml_string(rootXml, addHeader=True)
virtual bool equal(const KinematicConstraint &other, double margin) const
Check if two constraints are the same. For position constraints this means that:
Struct for containing the results of constraint evaluation.
Class for constraints on the XYZ position of a link.
srdf::ModelSharedPtr srdf_model
Representation of a robot's state. This includes position, velocity, acceleration and effort...
bool mobileReferenceFrame() const
If enabled and the specified frame is a mobile frame, return true. Otherwise, returns false...
int main(int argc, char **argv)
#define EXPECT_TRUE(args)
bool configure(const moveit_msgs::JointConstraint &jc)
Configure the constraint based on a moveit_msgs::JointConstraint.
virtual ConstraintEvaluationResult decide(const robot_state::RobotState &state, bool verbose=false) const
Decide whether the constraint is satisfied in the indicated state.