cart_trajectory_pt.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Apache License)
00003  *
00004  * Copyright (c) 2014, Southwest Research Institute
00005  *
00006  * Licensed under the Apache License, Version 2.0 (the "License");
00007  * you may not use this file except in compliance with the License.
00008  * You may obtain a copy of the License at
00009  *
00010  * http://www.apache.org/licenses/LICENSE-2.0
00011  *
00012  * Unless required by applicable law or agreed to in writing, software
00013  * distributed under the License is distributed on an "AS IS" BASIS,
00014  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00015  * See the License for the specific language governing permissions and
00016  * limitations under the License.
00017  */
00018 
00019 #include "descartes_trajectory/cart_trajectory_pt.h"
00020 #include "descartes_core/utils.h"
00021 #include "descartes_trajectory_test/cartesian_robot.h"
00022 #include <gtest/gtest.h>
00023 
00024 
00025 using namespace descartes_trajectory;
00026 using namespace descartes_core;
00027 using namespace descartes_trajectory_test;
00028 
00029 
00030 
00031 TEST(CartTrajPt, construction)
00032 {
00033   CartTrajectoryPt def();
00034 }
00035 
00036 TEST(CartTrajPt, getPoses)
00037 {
00038   const double POS_TOL = 2.0;
00039   const double POS_INC = 0.2;
00040 
00041   const double ORIENT_TOL = 2*M_PI;
00042   const double ORIENT_INC = M_PI/4;
00043 
00044   const double EPSILON = 0.001;
00045 
00046   const int NUM_SAMPLED_POS = pow((POS_TOL/POS_INC) + 1, 3.0);
00047   const int NUM_SAMPLED_ORIENT = pow((ORIENT_TOL/ORIENT_INC) + 1, 3.0);
00048   const int NUM_SAMPLED_BOTH = NUM_SAMPLED_POS * NUM_SAMPLED_ORIENT;
00049 
00050   ROS_INFO_STREAM("Expected samples, position: " << NUM_SAMPLED_POS
00051                   << ", orientation: " << NUM_SAMPLED_ORIENT
00052                   << ", both: " << NUM_SAMPLED_BOTH);
00053 
00054   ROS_INFO_STREAM("Initializing fuzzy position point");
00055   CartTrajectoryPt fuzzy_pos(TolerancedFrame(
00056                                utils::toFrame(0, 0, 0, 0, 0, 0),
00057                                ToleranceBase::createSymmetric<PositionTolerance>(0.0, 0.0, 0.0, POS_TOL + EPSILON),
00058                                ToleranceBase::createSymmetric<OrientationTolerance>(0.0, 0.0, 0.0, 0.0)),
00059                              POS_INC, ORIENT_INC);
00060 
00061   ROS_INFO_STREAM("Initializing fuzzy orientation point");
00062   CartTrajectoryPt fuzzy_orient(TolerancedFrame(
00063                                   utils::toFrame(0, 0, 0, 0, 0, 0),
00064                                   ToleranceBase::createSymmetric<PositionTolerance>(0.0, 0.0, 0.0, 0.0),
00065                                   ToleranceBase::createSymmetric<OrientationTolerance>(0.0, 0.0, 0.0, ORIENT_TOL + EPSILON)),
00066                                 POS_INC, ORIENT_INC);
00067 
00068   ROS_INFO_STREAM("Initializing fuzzy position/orientation point");
00069   CartTrajectoryPt fuzzy_both(TolerancedFrame(
00070                                 utils::toFrame(0, 0, 0, 0, 0, 0),
00071                                 ToleranceBase::createSymmetric<PositionTolerance>(0.0, 0.0, 0.0, POS_TOL + EPSILON),
00072                                 ToleranceBase::createSymmetric<OrientationTolerance>(0.0, 0.0, 0.0, ORIENT_TOL + EPSILON)),
00073                               POS_INC, ORIENT_INC);
00074 
00075 
00076   EigenSTL::vector_Affine3d solutions;
00077   std::vector<std::vector<double> >joint_solutions;
00078 
00079   ROS_INFO_STREAM("Testing fuzzy pos point");
00080   CartesianRobot robot(POS_TOL+2*EPSILON, ORIENT_TOL+2*EPSILON);
00081   fuzzy_pos.getCartesianPoses(robot, solutions);
00082   EXPECT_EQ(solutions.size(), NUM_SAMPLED_POS);
00083   fuzzy_pos.getJointPoses(robot,joint_solutions);
00084   EXPECT_EQ(joint_solutions.size(), NUM_SAMPLED_POS);
00085 
00086   ROS_INFO_STREAM("Testing fuzzy orient point");
00087   fuzzy_orient.getCartesianPoses(robot, solutions);
00088   EXPECT_EQ(solutions.size(), NUM_SAMPLED_ORIENT);
00089   fuzzy_orient.getJointPoses(robot,joint_solutions);
00090   EXPECT_EQ(joint_solutions.size(), NUM_SAMPLED_ORIENT);
00091 
00092   ROS_INFO_STREAM("Testing fuzzy both point");
00093   fuzzy_both.getCartesianPoses(robot, solutions);
00094   EXPECT_EQ(solutions.size(), NUM_SAMPLED_BOTH);
00095   fuzzy_both.getJointPoses(robot,joint_solutions);
00096   EXPECT_EQ(joint_solutions.size(), NUM_SAMPLED_BOTH);
00097 
00098   // TODO: Add tests for cartesian points outside of the robot workspace.  These
00099   // tests below seem to work, but predicting the number of samples isn't working.
00100   //  const double WS_FRACTION = 0.5;  //Reduces robot workspace
00101   //  const int LIMIT_SAMPLED_POS = pow(((WS_FRACTION * POS_TOL)/POS_INC) + 1, 3.0);
00102   //  const int LIMIT_SAMPLED_ORIENT = pow(((WS_FRACTION * ORIENT_TOL)/ORIENT_INC) + 1, 3.0);
00103   //  const int LIMIT_SAMPLED_BOTH = LIMIT_SAMPLED_POS * LIMIT_SAMPLED_ORIENT;
00104 
00105   //  CartesianRobot limited_robot(POS_TOL * WS_FRACTION + 2*EPSILON, ORIENT_TOL * WS_FRACTION + 2*EPSILON);
00106   //  fuzzy_pos.getCartesianPoses(limited_robot, solutions);
00107   //  EXPECT_EQ(solutions.size(), LIMIT_SAMPLED_POS);
00108 
00109   //  fuzzy_orient.getCartesianPoses(limited_robot, solutions);
00110   //  EXPECT_EQ(solutions.size(), LIMIT_SAMPLED_ORIENT);
00111 
00112   //  fuzzy_both.getCartesianPoses(limited_robot, solutions);
00113   //  EXPECT_EQ(solutions.size(), LIMIT_SAMPLED_BOTH);
00114 
00115 }
00116 
00117 
00118 TEST(CartTrajPt, zeroTolerance)
00119 {
00120 
00121   ROS_INFO_STREAM("Initializing zero tolerance cartesian point");
00122   CartTrajectoryPt zero_tol_pos(TolerancedFrame(
00123                                utils::toFrame(0, 0, 0, 0, 0, 0),
00124                                ToleranceBase::zeroTolerance<PositionTolerance>(0.0, 0.0, 0.0),
00125                                ToleranceBase::zeroTolerance<OrientationTolerance>(0.0, 0.0, 0.0)),
00126                              0, 0);
00127 
00128   EigenSTL::vector_Affine3d solutions;
00129   std::vector<std::vector<double> >joint_solutions;
00130 
00131   CartesianRobot robot;
00132   zero_tol_pos.getCartesianPoses(robot, solutions);
00133   EXPECT_EQ(solutions.size(), 1);
00134   zero_tol_pos.getJointPoses(robot,joint_solutions);
00135   EXPECT_EQ(joint_solutions.size(), 1);
00136 }
00137 
00138 TEST(CartTrajPt, closestJointPose)
00139 {
00140   const double POS_TOL = 0.5f;
00141   const double POS_INC = 0.2;
00142   const double ORIENT_TOL = 1.0;
00143   const double ORIENT_INC = 0.2;
00144   CartesianRobot robot(10,4);
00145 
00146   // declaring pose values
00147   const double x = 4.0f;
00148   const double y = 5.0f;
00149   const double z = 2.0f;
00150   const double rx = 0.0f;
00151   const double ry = 0.0f;
00152   const double rz = M_PI/4;
00153   std::vector<double> joint_pose                                                                                                                                                                                                                                                                                                                                                                                                                                                                = {x,y,z,rx,ry,rz};
00154   Eigen::Affine3d frame_pose = descartes_core::utils::toFrame(x,y,z,rx,ry,rz);
00155 
00156   ROS_INFO_STREAM("Initializing tolerance cartesian point");
00157   CartTrajectoryPt cart_point(TolerancedFrame(
00158                                 utils::toFrame(x,y,z,rx,ry,rz),
00159                                 ToleranceBase::createSymmetric<PositionTolerance>(x,y,z, POS_TOL),
00160                                 ToleranceBase::createSymmetric<OrientationTolerance>(rx,ry,rz, ORIENT_TOL)),
00161                               POS_INC, ORIENT_INC);
00162 
00163   ROS_INFO_STREAM("Testing getClosestJointPose(...)");
00164   std::vector<double> closest_joint_pose;
00165   EXPECT_TRUE(cart_point.getClosestJointPose(joint_pose,robot,closest_joint_pose));
00166 
00167   ROS_INFO_STREAM("Testing equality between seed joint pose and closest joint pose");
00168   EXPECT_EQ(joint_pose,closest_joint_pose);
00169 }


descartes_trajectory
Author(s): Jorge Nicho
autogenerated on Wed Aug 26 2015 11:21:27