Commit ea0c1076 authored by Joseph Mirabel's avatar Joseph Mirabel Committed by Joseph Mirabel
Browse files

Fix warnings related to steeringMethod::Straight in unit-test

parent 8c57fa14
......@@ -48,7 +48,7 @@
#include <hpp/core/interpolated-path.hh>
#include <hpp/core/hermite-path.hh>
#include <hpp/core/steering-method-straight.hh>
#include <hpp/core/steering-method/straight.hh>
#include <hpp/core/steering-method/hermite.hh>
#include <hpp/core/path-projector/global.hh>
......@@ -294,14 +294,14 @@ const char* traits_parabola::_func = "parabola";
struct traits_progressive {
typedef pathProjector::Progressive Proj_t;
typedef pathProjector::ProgressivePtr_t ProjPtr_t;
typedef SteeringMethodStraight SM_t;
typedef steeringMethod::Straight SM_t;
static const value_type projection_step;
static const char* _proj;
};
struct traits_global {
typedef pathProjector::Global Proj_t;
typedef pathProjector::GlobalPtr_t ProjPtr_t;
typedef SteeringMethodStraight SM_t;
typedef steeringMethod::Straight SM_t;
static const value_type projection_step;
static const char* _proj;
};
......
......@@ -31,7 +31,7 @@
#include <hpp/core/node.hh>
#include <hpp/core/nearest-neighbor.hh>
#include <hpp/core/steering-method-straight.hh>
#include <hpp/core/steering-method/straight.hh>
#include <hpp/core/weighed-distance.hh>
#include <pinocchio/multibody/joint/joint-variant.hpp>
#include <pinocchio/multibody/geometry.hpp>
......@@ -49,8 +49,8 @@ using hpp::pinocchio::JointPtr_t;
using hpp::pinocchio::Device;
using hpp::pinocchio::DevicePtr_t;
using hpp::core::Problem;
using hpp::core::SteeringMethodStraight;
using hpp::core::SteeringMethodStraightPtr_t;
using hpp::core::steeringMethod::Straight;
using hpp::core::steeringMethod::StraightPtr_t;
using hpp::core::RoadmapPtr_t;
using hpp::core::Roadmap;
using hpp::core::NodePtr_t;
......@@ -111,7 +111,7 @@ BOOST_AUTO_TEST_CASE (Roadmap1) {
// Create steering method
Problem p (robot);
SteeringMethodStraightPtr_t sm = SteeringMethodStraight::create (p);
StraightPtr_t sm = Straight::create (p);
// create roadmap
hpp::core::DistancePtr_t distance (WeighedDistance::createWithWeight
(robot, boost::assign::list_of (1)(1)));
......@@ -356,7 +356,7 @@ BOOST_AUTO_TEST_CASE (nearestNeighbor) {
// Create steering method
Problem p (robot);
SteeringMethodStraightPtr_t sm = SteeringMethodStraight::create (p);
StraightPtr_t sm = Straight::create (p);
// create roadmap
hpp::core::DistancePtr_t distance (WeighedDistance::createWithWeight
(robot, boost::assign::list_of (1)(1)));
......
......@@ -27,7 +27,7 @@
#include <hpp/pinocchio/liegroup.hh>
#include <hpp/core/problem.hh>
#include <hpp/core/steering-method-straight.hh>
#include <hpp/core/steering-method/straight.hh>
#include <hpp/core/steering-method/spline.hh>
#define TOSTR( x ) static_cast< std::ostringstream & >( ( std::ostringstream() << x ) ).str()
......
......@@ -28,7 +28,7 @@
#include <hpp/core/discretized-collision-checking.hh>
#include <hpp/core/path-validation-report.hh>
#include <hpp/core/problem.hh>
#include <hpp/core/steering-method-straight.hh>
#include <hpp/core/steering-method/straight.hh>
#include <hpp/core/steering-method/spline.hh>
#include <hpp/core/path/spline.hh>
......@@ -52,7 +52,7 @@ using hpp::core::PathValidationReportPtr_t;
using hpp::core::Problem;
using hpp::core::ProblemPtr_t;
using hpp::core::SteeringMethodPtr_t;
using hpp::core::SteeringMethodStraight;
using hpp::core::steeringMethod::Straight;
using hpp::core::ValidationReportPtr_t;
BOOST_AUTO_TEST_SUITE (test_hpp_core)
......@@ -68,7 +68,7 @@ BOOST_AUTO_TEST_CASE (continuous_collision_checking_straight)
// create steering method
Problem problem (robot);
SteeringMethodPtr_t sm (SteeringMethodStraight::create (problem));
SteeringMethodPtr_t sm (Straight::create (problem));
// create path validation objects
PathValidationPtr_t dichotomy (Dichotomy::create (robot, 0));
......
......@@ -29,7 +29,7 @@
#include <hpp/pinocchio/collision-object.hh>
#include <hpp/pinocchio/device.hh>
#include <hpp/core/steering-method-straight.hh>
#include <hpp/core/steering-method/straight.hh>
#include <hpp/core/path-optimization/gradient-based.hh>
#include <hpp/core/path-vector.hh>
#include <hpp/core/problem.hh>
......@@ -54,7 +54,7 @@ using hpp::core::PathVector;
using hpp::core::PathVectorPtr_t;
using hpp::core::Problem;
using hpp::core::SteeringMethodPtr_t;
using hpp::core::SteeringMethodStraight;
using hpp::core::steeringMethod::Straight;
using hpp::core::PathOptimizerPtr_t;
using hpp::core::pathOptimization::GradientBased;
......
......@@ -36,7 +36,7 @@
#include "hpp/core/basic-configuration-shooter.hh"
#include <hpp/core/connected-component.hh>
#include <hpp/core/node.hh>
#include <hpp/core/steering-method-straight.hh>
#include <hpp/core/steering-method/straight.hh>
#include "../src/nearest-neighbor/basic.hh"
#include "../src/nearest-neighbor/k-d-tree.hh"
......@@ -144,7 +144,7 @@ BOOST_AUTO_TEST_CASE (kdTree) {
ConfigurationShooterPtr_t confShoot = problem.configurationShooter();
nearestNeighbor::KDTree kdTree(robot,distance,30);
nearestNeighbor::Basic basic (distance);
SteeringMethodPtr_t sm = SteeringMethodStraight::create (&problem);
SteeringMethodPtr_t sm = steeringMethod::Straight::create (&problem);
// Add 4 connectedComponents with 2000 nodes each
ConfigurationPtr_t configuration;
......
......@@ -23,7 +23,7 @@
#include <hpp/core/path-vector.hh>
#include <hpp/core/problem.hh>
#include <hpp/core/steering-method-straight.hh>
#include <hpp/core/steering-method/straight.hh>
BOOST_AUTO_TEST_SUITE( test_hpp_core )
......@@ -43,8 +43,8 @@ using hpp::core::PathVector;
using hpp::core::PathVectorPtr_t;
using hpp::core::Problem;
using hpp::core::ProblemPtr_t;
using hpp::core::SteeringMethodStraight;
using hpp::core::SteeringMethodStraightPtr_t;
using hpp::core::steeringMethod::Straight;
using hpp::core::steeringMethod::StraightPtr_t;
using hpp::core::value_type;
HPP_PREDEF_CLASS (LocalPath);
......
Supports Markdown
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