Go to the documentation of this file.
   32 #include <gtest/gtest.h> 
   38 #define CREATE_PROBLEM(X, I) std::shared_ptr<X> problem = CreateProblem<X>(#X, I); 
   39 #define NUM_TRIALS 100 
   42 #if EIGEN_VERSION_AT_LEAST(3, 3, 0) 
   45     if (
A.rows() != 
B.rows())
 
   47         throw std::runtime_error(
"Hessian dimension mismatch");
 
   51     for (
int i = 0; 
i < 
A.rows(); ++
i)
 
   60 std::shared_ptr<T> 
CreateProblem(
const std::string& name, 
int derivative)
 
   62     TEST_COUT << 
"Creating " << 
name << 
" with derivatives " << derivative;
 
   66     init.AddProperty(
Property(
"DerivativeOrder", 
false, derivative));
 
   83         Eigen::MatrixXd 
J = Eigen::MatrixXd::Zero(J0.rows(), J0.cols());
 
   86             Eigen::VectorXd 
x = 
x0;
 
   89             J.col(
i) = (task.
Phi - y0) / 
h;
 
   91         double errJ = (
J - J0).norm();
 
   99             ADD_FAILURE() << 
"Jacobian error out of bounds: " << errJ;
 
  119         for (
int j = 0; j < 
problem->N; ++j)
 
  124             const Eigen::MatrixXd J1 = 
problem->jacobian;
 
  128             const Eigen::MatrixXd J2 = 
problem->jacobian;
 
  131                 for (
int k = 0; k < 
problem->length_jacobian; ++k)
 
  133                     H_fd(k)(
i, j) = (J1(k, 
i) - J2(k, 
i)) / (2.0 * 
h);
 
  138         for (
int i = 0; 
i < H_fd.rows(); ++
i) errH += (H_fd(
i) - H_task(
i)).norm();
 
  143             for (
int i = 0; 
i < dH.rows(); ++
i)
 
  152             ADD_FAILURE() << 
"Hessian error out of bounds: " << errH;
 
  169         Eigen::MatrixXd 
J = Eigen::MatrixXd::Zero(J0.rows(), J0.cols());
 
  172             Eigen::VectorXd 
x = 
x0;
 
  175             J.col(
i) = (task.
Phi[
t] - y0) / 
h;
 
  177         double errJ = (
J - J0).norm();
 
  185             ADD_FAILURE() << 
"Jacobian error out of bounds: " << errJ;
 
  205         for (
int j = 0; j < 
problem->N; ++j)
 
  210             const Eigen::MatrixXd J1 = 
problem->jacobian[
t];
 
  214             const Eigen::MatrixXd J2 = 
problem->jacobian[
t];
 
  217                 for (
int k = 0; k < 
problem->length_jacobian; ++k)
 
  219                     H_fd(k)(
i, j) = (J1(k, 
i) - J2(k, 
i)) / (2.0 * 
h);
 
  224         for (
int i = 0; 
i < H_fd.rows(); ++
i) errH += (H_fd(
i) - H_task(
i)).norm();
 
  229             for (
int i = 0; 
i < dH.rows(); ++
i)
 
  238             ADD_FAILURE() << 
"Hessian error out of bounds: " << errH;
 
  248         std::vector<Eigen::VectorXd> 
X(3);
 
  249         std::vector<Eigen::MatrixXd> 
J(3);
 
  250         for (
int d = 0; 
d < 3; ++
d)
 
  253             Eigen::VectorXd 
x = 
problem->GetStartState();
 
  269         if (!(
X[0] == 
X[1] && 
X[1] == 
X[2]))
 
  270             ADD_FAILURE() << 
"Cost FK is inconsistent!";
 
  272             ADD_FAILURE() << 
"Cost Jacobians are inconsistent!";
 
  274     catch (
const std::exception& e)
 
  276         ADD_FAILURE() << 
"Uncaught exception! " << e.what();
 
  284         std::vector<Eigen::VectorXd> 
X(3);
 
  285         std::vector<Eigen::MatrixXd> 
J(3);
 
  286         for (
int d = 0; 
d < 3; ++
d)
 
  289             Eigen::VectorXd 
x = 
problem->GetStartState();
 
  305         if (!(
X[0] == 
X[1] && 
X[1] == 
X[2]))
 
  306             ADD_FAILURE() << 
"Cost FK is inconsistent!";
 
  308             ADD_FAILURE() << 
"Cost Jacobians are inconsistent!";
 
  310     catch (
const std::exception& e)
 
  312         ADD_FAILURE() << 
"Uncaught exception! " << e.what();
 
  320         std::vector<Eigen::VectorXd> 
X(9);
 
  321         std::vector<Eigen::MatrixXd> 
J(6);  
 
  322         for (
int d = 0; 
d < 3; ++
d)
 
  325             Eigen::VectorXd 
x = 
problem->GetStartState();
 
  326             TEST_COUT << 
"EndPoseProblem: Testing problem update";
 
  328             TEST_COUT << 
"EndPoseProblem::Update() - Test passed";
 
  330                 TEST_COUT << 
"EndPoseProblem: Testing cost";
 
  344                 TEST_COUT << 
"EndPoseProblem: Testing equality";
 
  358                 TEST_COUT << 
"EndPoseProblem: Testing inequality";
 
  371         if (!(
X[0] == 
X[1] && 
X[1] == 
X[2]))
 
  372             ADD_FAILURE() << 
"EndPoseProblem: Cost value computation is inconsistent!";
 
  374             ADD_FAILURE() << 
"EndPoseProblem: Cost Jacobians are inconsistent!";
 
  375         if (!(
X[3] == 
X[4] && 
X[4] == 
X[5]))
 
  376             ADD_FAILURE() << 
"EndPoseProblem: Equality value computation is inconsistent!";
 
  378             ADD_FAILURE() << 
"EndPoseProblem: Equality Jacobians are inconsistent!";
 
  379         if (!(
X[6] == 
X[7] && 
X[7] == 
X[8]))
 
  380             ADD_FAILURE() << 
"EndPoseProblem: Inequality value computation is inconsistent!";
 
  382             ADD_FAILURE() << 
"EndPoseProblem: Inequality Jacobians are inconsistent!";
 
  384     catch (
const std::exception& e)
 
  386         ADD_FAILURE() << 
"Uncaught exception! " << e.what();
 
  399         for (
int t = 0; 
t < 
T; ++
t)
 
  401             std::vector<Eigen::VectorXd> 
X(3);
 
  402             std::vector<Eigen::MatrixXd> 
J(3);
 
  403             for (
int d = 0; 
d < 3; ++
d)
 
  406                 Eigen::VectorXd 
x = 
problem->GetStartState();
 
  422             if (!(
X[0] == 
X[1] && 
X[1] == 
X[2]))
 
  423                 ADD_FAILURE() << 
"Cost FK is inconsistent!";
 
  425                 ADD_FAILURE() << 
"Cost Jacobians are inconsistent!";
 
  428     catch (
const std::exception& e)
 
  430         ADD_FAILURE() << 
"Uncaught exception! " << e.what();
 
  443         for (
int t = 0; 
t < 
T; ++
t)
 
  445             std::vector<Eigen::VectorXd> 
X(3);
 
  446             std::vector<Eigen::MatrixXd> 
J(3);
 
  447             for (
int d = 0; 
d < 3; ++
d)
 
  450                 Eigen::VectorXd 
x = 
problem->GetStartState();
 
  451                 TEST_COUT << 
"BoundedTimeIndexedProblem: Testing problem update";
 
  453                 TEST_COUT << 
"BoundedTimeIndexedProblem::Update(x): Test passed";
 
  455                 TEST_COUT << 
"BoundedTimeIndexedProblem: Testing cost";
 
  467                 ADD_FAILURE() << 
"BoundedTimeIndexedProblem: cost value computation is inconsistent!";
 
  469                 ADD_FAILURE() << 
"BoundedTimeIndexedProblem: cost Jacobians are inconsistent!";
 
  472     catch (
const std::exception& e)
 
  474         ADD_FAILURE() << 
"Uncaught exception! " << e.what();
 
  487         for (
int t = 0; 
t < 
T; ++
t)
 
  489             std::vector<Eigen::VectorXd> 
X(9);
 
  490             std::vector<Eigen::MatrixXd> 
J(9);
 
  491             for (
int d = 0; 
d < 3; ++
d)
 
  494                 Eigen::VectorXd 
x = 
problem->GetStartState();
 
  540             if (!(
X[0] == 
X[1] && 
X[1] == 
X[2]))
 
  541                 ADD_FAILURE() << 
"Cost FK is inconsistent!";
 
  543                 ADD_FAILURE() << 
"Cost Jacobians are inconsistent!";
 
  544             if (!(
X[3] == 
X[4] && 
X[4] == 
X[5]))
 
  545                 ADD_FAILURE() << 
"Equality FK is inconsistent!";
 
  547                 ADD_FAILURE() << 
"Equality Jacobians are inconsistent!";
 
  548             if (!(
X[6] == 
X[7] && 
X[7] == 
X[8]))
 
  549                 ADD_FAILURE() << 
"Inequality FK is inconsistent!";
 
  551                 ADD_FAILURE() << 
"Inequality Jacobians are inconsistent!";
 
  554     catch (
const std::exception& e)
 
  556         ADD_FAILURE() << 
"Uncaught exception! " << e.what();
 
  565         Eigen::VectorXd 
x = 
problem->GetStartState();
 
  569         if (!
problem->IsStateValid(
x)) ADD_FAILURE() << 
"Start state is invalid!";
 
  571     catch (
const std::exception& e)
 
  573         ADD_FAILURE() << 
"Uncaught exception! " << e.what();
 
  582         Eigen::VectorXd 
x = 
problem->GetStartState();
 
  586         if (!
problem->IsValid(
x, 0.0)) ADD_FAILURE() << 
"Start state is invalid!";
 
  588     catch (
const std::exception& e)
 
  590         ADD_FAILURE() << 
"Uncaught exception! " << e.what();
 
  594 int main(
int argc, 
char** argv)
 
  596     testing::InitGoogleTest(&argc, argv);
 
  597     int ret = RUN_ALL_TESTS();
 
  
void init(bool compute_local_aabb=true)
int main(int argc, char **argv)
std::vector< Hessian > hessian
template TMatrix3< double > operator-(const Matrix3< double > &m1, const TMatrix3< double > &m2)
std::vector< TaskSpaceVector > Phi
static std::shared_ptr< exotica::PlanningProblem > CreateProblem(const Initializer &init)
#define CREATE_PROBLEM(X, I)
Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 > Hessian
void testHessianEndPose(std::shared_ptr< T > problem, EndPoseTask &task, double eps=1e-4, double h=1e-5)
TEST(ExoticaProblems, UnconstrainedEndPoseProblem)
void testJacobianEndPose(std::shared_ptr< T > problem, EndPoseTask &task, double eps=1e-4, double h=1e-5)
void testHessianTimeIndexed(std::shared_ptr< T > problem, TimeIndexedTask &task, int t, double eps=1e-4, double h=1e-5)
std::shared_ptr< T > CreateProblem(const std::string &name, int derivative)
std::vector< Eigen::MatrixXd > jacobian
static Initializer Load(std::string file_name, bool parsePathAsXML=false)
void testJacobianTimeIndexed(std::shared_ptr< T > problem, TimeIndexedTask &task, int t, double eps=1e-4, double h=1e-5)
bool isApprox(const Box &s1, const Box &s2, const FCL_REAL tol)