Commit cb72b669 authored by Joseph Mirabel's avatar Joseph Mirabel
Browse files

Fix unit-tests compilation

* following the change of the typedef ProblemPtr_t
parent ceb3c7f7
......@@ -135,8 +135,8 @@ BOOST_AUTO_TEST_CASE (hermitePath)
{
DevicePtr_t dev = createRobot ();
BOOST_REQUIRE (dev);
Problem problem (dev);
steeringMethod::HermitePtr_t hermiteSM = steeringMethod::Hermite::create(&problem);
ProblemPtr_t problem = Problem::create(dev);
steeringMethod::HermitePtr_t hermiteSM = steeringMethod::Hermite::create(problem);
Configuration_t q0 (dev->configSize()); q0 << -1, -1;
Configuration_t q2 (dev->configSize()); q2 << 1, 1;
......
......@@ -306,22 +306,22 @@ BOOST_AUTO_TEST_CASE_TEMPLATE (projectors, traits, test_types)
{
DevicePtr_t dev = createRobot();
BOOST_REQUIRE (dev);
Problem problem (dev);
ProblemPtr_t problem = Problem::create(dev);
ConstraintSetPtr_t c = createConstraints (dev);
DifferentiableFunctionPtr_t func = traits::func (dev);
c->configProjector ()->add (Implicit::create (func));
problem.steeringMethod(traits::SM_t::create (problem));
problem.steeringMethod ()->constraints (c);
problem->steeringMethod(traits::SM_t::create (*problem));
problem->steeringMethod ()->constraints (c);
for (int c = 0; c < 2; ++c) {
if (c == 0)
problem.setParameter ("PathProjection/HessianBound", Parameter((value_type)-1));
problem->setParameter ("PathProjection/HessianBound", Parameter((value_type)-1));
else
problem.setParameter ("PathProjection/HessianBound", Parameter(traits::K));
problem->setParameter ("PathProjection/HessianBound", Parameter(traits::K));
typename traits::ProjPtr_t projector =
traits::Proj_t::create (problem, traits::projection_step);
traits::Proj_t::create (*problem, traits::projection_step);
std::cout << "========================================\n";
......@@ -331,7 +331,7 @@ BOOST_AUTO_TEST_CASE_TEMPLATE (projectors, traits, test_types)
// HPP_DEFINE_TIMECOUNTER(projector);
traits::make_conf (q1, q2, i);
PathPtr_t path = (*problem.steeringMethod ()) (q1,q2);
PathPtr_t path = (*problem->steeringMethod ()) (q1,q2);
PathPtr_t projection;
// Averaging the projection
......
......@@ -112,11 +112,11 @@ BOOST_AUTO_TEST_CASE (extracted)
{
DevicePtr_t dev = createRobot();
BOOST_REQUIRE (dev);
Problem problem (dev);
ProblemPtr_t problem = Problem::create(dev);
Configuration_t q1 (dev->configSize()); q1 << 0;
Configuration_t q2 (dev->configSize()); q2 << 1;
PathPtr_t p1 = (*problem.steeringMethod()) (q1, q2), p2;
PathPtr_t p1 = (*problem->steeringMethod()) (q1, q2), p2;
p2 = p1->extract (Pair_t (0.5, 1));
checkAt (p1, 0.5, p2, 0.0);
......@@ -140,7 +140,7 @@ BOOST_AUTO_TEST_CASE (subchain)
{
DevicePtr_t dev = createRobot2(); // 10 translations
BOOST_REQUIRE (dev);
Problem problem (dev);
ProblemPtr_t problem = Problem::create(dev);
segments_t intervals;
intervals.push_back(segment_t (0,3));
......@@ -150,7 +150,7 @@ BOOST_AUTO_TEST_CASE (subchain)
Configuration_t q2 (Configuration_t::Ones(dev->configSize()));
q2.tail<5>().setConstant(-1);
PathPtr_t p1 = (*problem.steeringMethod()) (q1, q2), p2;
PathPtr_t p1 = (*problem->steeringMethod()) (q1, q2), p2;
p2 = SubchainPath::create(p1, intervals, intervals);
BOOST_CHECK(p2->outputSize() == 6);
......
......@@ -20,4 +20,5 @@ SET_TARGET_PROPERTIES(example PROPERTIES PREFIX ""
)
TARGET_LINK_LIBRARIES(example ${LIBRARY_NAME})
PKG_CONFIG_USE_DEPENDENCY(example hpp-pinocchio)
#INSTALL(TARGETS example DESTINATION lib/hppPlugins)
......@@ -41,6 +41,7 @@ BOOST_AUTO_TEST_CASE (memory_deallocation)
SteeringMethodWkPtr_t sm = problem->steeringMethod();
DistanceWkPtr_t distance = problem->distance ();
RoadmapWkPtr_t roadmap = ps->roadmap ();
problem.reset();
delete ps;
......
......@@ -84,8 +84,8 @@ BOOST_AUTO_TEST_CASE (Roadmap1) {
DevicePtr_t robot = createRobot();
// Create steering method
Problem p (robot);
StraightPtr_t sm = Straight::create (p);
ProblemPtr_t p = Problem::create(robot);
StraightPtr_t sm = Straight::create (*p);
// create roadmap
hpp::core::DistancePtr_t distance (WeighedDistance::createWithWeight
(robot, vector_t::Ones(2)));
......@@ -307,8 +307,8 @@ BOOST_AUTO_TEST_CASE (nearestNeighbor) {
DevicePtr_t robot = createRobot();
// Create steering method
Problem p (robot);
StraightPtr_t sm = Straight::create (p);
ProblemPtr_t p = Problem::create(robot);
StraightPtr_t sm = Straight::create (*p);
// create roadmap
hpp::core::DistancePtr_t distance (WeighedDistance::createWithWeight
(robot, vector_t::Ones(2)));
......
......@@ -82,7 +82,7 @@ template <int SplineType> void compare_to_straight_path ()
DevicePtr_t dev = createRobot();
BOOST_REQUIRE (dev);
Problem problem (dev);
ProblemPtr_t problem = Problem::create(dev);
Configuration_t q1 (::pinocchio::randomConfiguration(dev->model()));
Configuration_t q2 (::pinocchio::randomConfiguration(dev->model()));
......@@ -91,11 +91,11 @@ template <int SplineType> void compare_to_straight_path ()
difference<RnxSOnLieGroupMap> (dev, q2, q1, v);
// create StraightPath
PathPtr_t sp = (*problem.steeringMethod()) (q1, q2);
PathPtr_t sp = (*problem->steeringMethod()) (q1, q2);
// value_type length = sp->length();
// Create linear spline
typename SM_t::Ptr_t sm (SM_t::create (problem));
typename SM_t::Ptr_t sm (SM_t::create (*problem));
PathPtr_t ls_abstract = (*sm) (q1, q2);
typename path_t::Ptr_t ls = HPP_DYNAMIC_PTR_CAST(path_t, ls_abstract);
......@@ -153,7 +153,7 @@ void check_velocity_bounds ()
DevicePtr_t dev = createRobot();
BOOST_REQUIRE (dev);
Problem problem (dev);
ProblemPtr_t problem = Problem::create(dev);
Configuration_t q1 (::pinocchio::randomConfiguration(dev->model()));
Configuration_t q2 (::pinocchio::randomConfiguration(dev->model()));
......@@ -163,7 +163,7 @@ void check_velocity_bounds ()
// Create spline
typename SM_t::Ptr_t sm (SM_t::create (problem));
typename SM_t::Ptr_t sm (SM_t::create (*problem));
PathPtr_t spline = sm->steer (q1, orders, v1, q2, orders, v2);
vector_t vb1 (vector_t::Random(dev->numberDof())), vb2 = vb1;
......
......@@ -133,8 +133,8 @@ BOOST_AUTO_TEST_CASE (continuous_validation_straight)
robot->numberDeviceData (4);
// create steering method
Problem problem (robot);
SteeringMethodPtr_t sm (Straight::create (problem));
ProblemPtr_t problem = Problem::create(robot);
SteeringMethodPtr_t sm (Straight::create (*problem));
// create path validation objects
PathValidationPtr_t dichotomy (Dichotomy::create (robot, 0));
......@@ -257,8 +257,8 @@ template <typename SplineSteeringMethod> void test_spline_steering_method ()
robot->numberDeviceData (4);
// create steering method
Problem problem (robot);
typename SplineSteeringMethod::Ptr_t sm (SplineSteeringMethod::create (problem));
ProblemPtr_t problem = Problem::create(robot);
typename SplineSteeringMethod::Ptr_t sm (SplineSteeringMethod::create (*problem));
// create path validation objects
// PathValidationPtr_t dichotomy (Dichotomy::create (robot, 0));
......
......@@ -86,21 +86,21 @@ BOOST_AUTO_TEST_CASE (BFGS)
q3 (0) = s; q3 (1) = s; q3 (2) = s; q3 (3) = s;
q4 (0) = 1; q4 (1) = 0; q4 (2) = 1; q4 (3) = 0;
Problem problem (robot);
SteeringMethodPtr_t sm = problem.steeringMethod ();
ProblemPtr_t problem = Problem::create(robot);
SteeringMethodPtr_t sm = problem->steeringMethod ();
PathVectorPtr_t path = PathVector::create (robot->configSize (),
robot->numberDof ());
path->appendPath ((*sm) (q0, q1));
path->appendPath ((*sm) (q1, q2));
path->appendPath ((*sm) (q2, q3));
path->appendPath ((*sm) (q3, q4));
problem.setParameter ("SplineGradientBased/alphaInit",
problem->setParameter ("SplineGradientBased/alphaInit",
hpp::core::Parameter (1.));
problem.setParameter ("SplineGradientBased/costThreshold",
problem->setParameter ("SplineGradientBased/costThreshold",
hpp::core::Parameter (1e-6));
PathOptimizerPtr_t pathOptimizer
(pathOptimization::SplineGradientBased<path::BernsteinBasis, 1>::create
(problem));
(*problem));
PathVectorPtr_t optimizedPath (pathOptimizer->optimize (path));
Configuration_t p0 (robot->configSize ());
Configuration_t p1 (robot->configSize ());
......
......@@ -138,13 +138,13 @@ BOOST_AUTO_TEST_CASE (kdTree) {
// Build Distance, nearestNeighbor, KDTree
Problem problem (robot);
ProblemPtr_t problem = Problem::create(robot);
WeighedDistancePtr_t distance = WeighedDistance::create(robot);
problem.distance (distance);
ConfigurationShooterPtr_t confShoot = problem.configurationShooter();
problem->distance (distance);
ConfigurationShooterPtr_t confShoot = problem->configurationShooter();
nearestNeighbor::KDTree kdTree(robot,distance,30);
nearestNeighbor::Basic basic (distance);
SteeringMethodPtr_t sm = steeringMethod::Straight::create (&problem);
SteeringMethodPtr_t sm = steeringMethod::Straight::create (problem);
// Add 4 connectedComponents with 2000 nodes each
ConfigurationPtr_t configuration;
......
......@@ -93,12 +93,12 @@ BOOST_AUTO_TEST_CASE (kinodynamic) {
// Create steering method
Problem p = Problem (robot);
p.setParameter(std::string("Kinodynamic/velocityBound"),Parameter(vMax));
p.setParameter(std::string("Kinodynamic/accelerationBound"),Parameter(aMax));
ProblemPtr_t p = Problem::create(robot);
p->setParameter(std::string("Kinodynamic/velocityBound"),Parameter(vMax));
p->setParameter(std::string("Kinodynamic/accelerationBound"),Parameter(aMax));
steeringMethod::KinodynamicPtr_t sm = steeringMethod::Kinodynamic::create (p);
KinodynamicDistancePtr_t dist = KinodynamicDistance::createFromProblem(p);
steeringMethod::KinodynamicPtr_t sm = steeringMethod::Kinodynamic::create (*p);
KinodynamicDistancePtr_t dist = KinodynamicDistance::createFromProblem(*p);
// try to connect several states : (notation : sx = (px, vx, ax)
Configuration_t q0 (robot->currentConfiguration());
......@@ -504,12 +504,12 @@ BOOST_AUTO_TEST_CASE (kinodynamic_aMax1) {
// Create steering method
Problem p = Problem (robot);
p.setParameter(std::string("Kinodynamic/velocityBound"),Parameter(vMax));
p.setParameter(std::string("Kinodynamic/accelerationBound"),Parameter(aMax));
ProblemPtr_t p = Problem::create(robot);
p->setParameter(std::string("Kinodynamic/velocityBound"),Parameter(vMax));
p->setParameter(std::string("Kinodynamic/accelerationBound"),Parameter(aMax));
steeringMethod::KinodynamicPtr_t sm = steeringMethod::Kinodynamic::create (p);
KinodynamicDistancePtr_t dist = KinodynamicDistance::createFromProblem(p);
steeringMethod::KinodynamicPtr_t sm = steeringMethod::Kinodynamic::create (*p);
KinodynamicDistancePtr_t dist = KinodynamicDistance::createFromProblem(*p);
// try to connect several states : (notation : sx = (px, vx, ax)
Configuration_t q0 (robot->currentConfiguration());
......@@ -586,14 +586,14 @@ BOOST_AUTO_TEST_CASE (kinodynamicOriented) {
// Create steering method
Problem p = Problem (robot);
p.setParameter(std::string("Kinodynamic/velocityBound"),Parameter(vMax));
p.setParameter(std::string("Kinodynamic/accelerationBound"),Parameter(aMax));
p.setParameter(std::string("Kinodynamic/forceOrientation"),Parameter(true));
ProblemPtr_t p = Problem::create(robot);
p->setParameter(std::string("Kinodynamic/velocityBound"),Parameter(vMax));
p->setParameter(std::string("Kinodynamic/accelerationBound"),Parameter(aMax));
p->setParameter(std::string("Kinodynamic/forceOrientation"),Parameter(true));
steeringMethod::KinodynamicPtr_t sm = steeringMethod::Kinodynamic::create (p);
KinodynamicDistancePtr_t dist = KinodynamicDistance::createFromProblem(p);
steeringMethod::KinodynamicPtr_t sm = steeringMethod::Kinodynamic::create (*p);
KinodynamicDistancePtr_t dist = KinodynamicDistance::createFromProblem(*p);
KinodynamicOrientedPathPtr_t pathKino,extractedPathKino;
PathPtr_t path,extractedPath;
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment