Unverified Commit 7f791ea8 authored by Guilhem Saurel's avatar Guilhem Saurel Committed by GitHub
Browse files

Merge pull request #58 from loco-3d/nd_curves

curves → ndcurves, fix #2
parents 991a37b3 8fe7090a
......@@ -3,7 +3,7 @@ import matplotlib.pyplot as plt
import numpy as np
from numpy import array
from .curves import bezier
from .ndcurves import bezier
eigenpy.switchToNumpyArray()
......
#include "python_variables.h"
#include "curves/python/python_definitions.h"
#include "ndcurves/python/python_definitions.h"
#include <Eigen/Core>
namespace curves {
namespace ndcurves {
std::vector<linear_variable_t> matrix3DFromEigenArray(const point_list3_t& matrices, const point_list3_t& vectors) {
if (vectors.cols() * 3 != matrices.cols()) {
throw std::invalid_argument("vectors.cols() * 3 != matrices.cols()");
......@@ -71,4 +71,4 @@ linear_variable_t* wayPointsToLists(const bezier_linear_variable_t& self) {
return new linear_variable_t(matrices.transpose(), vectors.transpose());
}
} // namespace curves
} // namespace ndcurves
#include "curves/fwd.h"
#include "curves/linear_variable.h"
#include "curves/bezier_curve.h"
#include "curves/constant_curve.h"
#include "curves/polynomial.h"
#include "curves/exact_cubic.h"
#include "curves/curve_constraint.h"
#include "curves/curve_conversion.h"
#include "curves/bernstein.h"
#include "curves/cubic_hermite_spline.h"
#include "curves/piecewise_curve.h"
#include "curves/so3_linear.h"
#include "curves/se3_curve.h"
#include "curves/sinusoidal.h"
#include "curves/python/python_definitions.h"
#include "ndcurves/fwd.h"
#include "ndcurves/linear_variable.h"
#include "ndcurves/bezier_curve.h"
#include "ndcurves/constant_curve.h"
#include "ndcurves/polynomial.h"
#include "ndcurves/exact_cubic.h"
#include "ndcurves/curve_constraint.h"
#include "ndcurves/curve_conversion.h"
#include "ndcurves/bernstein.h"
#include "ndcurves/cubic_hermite_spline.h"
#include "ndcurves/piecewise_curve.h"
#include "ndcurves/so3_linear.h"
#include "ndcurves/se3_curve.h"
#include "ndcurves/sinusoidal.h"
#include "ndcurves/python/python_definitions.h"
#include <eigenpy/memory.hpp>
#include <eigenpy/eigenpy.hpp>
#include <eigenpy/geometry.hpp>
......@@ -23,7 +23,7 @@
#ifndef _VARIABLES_PYTHON_BINDINGS
#define _VARIABLES_PYTHON_BINDINGS
namespace curves {
namespace ndcurves {
static const int dim = 3;
typedef linear_variable<real, true> linear_variable_t;
typedef quadratic_variable<real> quadratic_variable_t;
......@@ -62,29 +62,29 @@ struct LinearBezierVector {
};
/*** TEMPLATE SPECIALIZATION FOR PYTHON ****/
} // namespace curves
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::bernstein_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::curve_constraints_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::matrix_x_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::pointX_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::linear_variable_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::bezier_linear_variable_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::matrix_pair)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::polynomial_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::exact_cubic_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::bezier_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::constant_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::cubic_hermite_spline_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::piecewise_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::polynomial3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::exact_cubic3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::bezier3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::constant3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::cubic_hermite_spline3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::piecewise3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::SO3Linear_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::SE3Curve_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::sinusoidal_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(curves::piecewise_SE3_t)
} // namespace ndcurves
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::bernstein_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::curve_constraints_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::matrix_x_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::pointX_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::linear_variable_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::bezier_linear_variable_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::matrix_pair)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::polynomial_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::exact_cubic_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::bezier_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::constant_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::cubic_hermite_spline_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::piecewise_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::polynomial3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::exact_cubic3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::bezier3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::constant3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::cubic_hermite_spline3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::piecewise3_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::SO3Linear_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::SE3Curve_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::sinusoidal_t)
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(ndcurves::piecewise_SE3_t)
#endif //_VARIABLES_PYTHON_BINDINGS
......@@ -4,7 +4,7 @@ import eigenpy
from numpy import array, dot, identity, zeros
# importing the bezier curve class
from curves import bezier
from ndcurves import bezier
eigenpy.switchToNumpyArray()
......@@ -30,7 +30,7 @@ class TestNotebook(unittest.TestCase):
fNumSamples = float(numSamples)
ptsTime = [(ref(float(t) / fNumSamples), float(t) / fNumSamples) for t in range(numSamples + 1)]
from curves.optimization import (problem_definition, setup_control_points)
from ndcurves.optimization import (problem_definition, setup_control_points)
# dimension of our problem (here 3 as our curve is 3D)
dim = 3
......@@ -80,7 +80,7 @@ class TestNotebook(unittest.TestCase):
res = quadprog_solve_qp(A, b)
fitBezier = evalAndPlot(variableBezier, res)
from curves.optimization import constraint_flag
from ndcurves.optimization import constraint_flag
pD.flag = constraint_flag.INIT_POS | constraint_flag.END_POS
# set initial position
......
......@@ -4,7 +4,7 @@ import eigenpy
from numpy import array, matrix, zeros
from numpy.linalg import norm
from curves.optimization import (constraint_flag, generate_integral_problem, integral_cost_flag, problem_definition,
from ndcurves.optimization import (constraint_flag, generate_integral_problem, integral_cost_flag, problem_definition,
setup_control_points)
eigenpy.switchToNumpyArray()
......
......@@ -9,15 +9,15 @@ class TestRegistration(unittest.TestCase):
"""
def test_pinocchio_then_curves(self):
import pinocchio
import curves
import ndcurves
self.assertTrue(hasattr(pinocchio, 'Quaternion'))
self.assertTrue(hasattr(curves, 'Quaternion'))
self.assertTrue(hasattr(ndcurves, 'Quaternion'))
def test_curves_then_pinocchio(self):
import curves
import ndcurves
import pinocchio
self.assertTrue(hasattr(pinocchio, 'Quaternion'))
self.assertTrue(hasattr(curves, 'Quaternion'))
self.assertTrue(hasattr(ndcurves, 'Quaternion'))
if __name__ == '__main__':
......
......@@ -30,7 +30,7 @@
},
{
"cell_type": "code",
"execution_count": 1,
"execution_count": 33,
"metadata": {},
"outputs": [
{
......@@ -58,10 +58,10 @@
"eigenpy.switchToNumpyArray()\n",
"\n",
"#importing the bezier curve class\n",
"from curves import (bezier)\n",
"from ndcurves import (bezier)\n",
"\n",
"#importing tools to plot bezier curves\n",
"from curves.plot import (plotBezier)\n",
"from ndcurves.plot import (plotBezier)\n",
"from mpl_toolkits.mplot3d import Axes3D\n",
"import matplotlib.pyplot as plt\n",
"import numpy as np\n",
......@@ -85,7 +85,7 @@
},
{
"cell_type": "code",
"execution_count": 2,
"execution_count": 34,
"metadata": {},
"outputs": [
{
......@@ -127,11 +127,11 @@
},
{
"cell_type": "code",
"execution_count": 3,
"execution_count": 35,
"metadata": {},
"outputs": [],
"source": [
"from curves.optimization import (problem_definition, setup_control_points)\n",
"from ndcurves.optimization import (problem_definition, setup_control_points)\n",
"\n",
"#dimension of our problem (here 3 as our curve is 3D)\n",
"dim = 3\n",
......@@ -155,7 +155,7 @@
},
{
"cell_type": "code",
"execution_count": 4,
"execution_count": 36,
"metadata": {},
"outputs": [
{
......@@ -191,7 +191,7 @@
},
{
"cell_type": "code",
"execution_count": 5,
"execution_count": 37,
"metadata": {},
"outputs": [
{
......@@ -219,7 +219,7 @@
},
{
"cell_type": "code",
"execution_count": 6,
"execution_count": 38,
"metadata": {},
"outputs": [],
"source": [
......@@ -247,7 +247,7 @@
},
{
"cell_type": "code",
"execution_count": 7,
"execution_count": 39,
"metadata": {},
"outputs": [],
"source": [
......@@ -295,7 +295,7 @@
},
{
"cell_type": "code",
"execution_count": 8,
"execution_count": 40,
"metadata": {},
"outputs": [
{
......@@ -335,7 +335,7 @@
},
{
"cell_type": "code",
"execution_count": 9,
"execution_count": 41,
"metadata": {},
"outputs": [
{
......@@ -376,7 +376,7 @@
},
{
"cell_type": "code",
"execution_count": 10,
"execution_count": 42,
"metadata": {},
"outputs": [],
"source": [
......@@ -400,7 +400,7 @@
},
{
"cell_type": "code",
"execution_count": 11,
"execution_count": 43,
"metadata": {},
"outputs": [
{
......@@ -424,7 +424,7 @@
},
{
"cell_type": "code",
"execution_count": 12,
"execution_count": 44,
"metadata": {},
"outputs": [
{
......@@ -461,7 +461,7 @@
},
{
"cell_type": "code",
"execution_count": 13,
"execution_count": 45,
"metadata": {},
"outputs": [],
"source": [
......@@ -482,7 +482,7 @@
},
{
"cell_type": "code",
"execution_count": 14,
"execution_count": 46,
"metadata": {},
"outputs": [
{
......@@ -509,7 +509,7 @@
},
{
"cell_type": "code",
"execution_count": 15,
"execution_count": 47,
"metadata": {},
"outputs": [
{
......@@ -543,7 +543,7 @@
},
{
"cell_type": "code",
"execution_count": 17,
"execution_count": 48,
"metadata": {},
"outputs": [
{
......@@ -575,7 +575,7 @@
},
{
"cell_type": "code",
"execution_count": 18,
"execution_count": 49,
"metadata": {},
"outputs": [
{
......@@ -614,7 +614,7 @@
},
{
"cell_type": "code",
"execution_count": 19,
"execution_count": 50,
"metadata": {},
"outputs": [
{
......@@ -669,7 +669,7 @@
},
{
"cell_type": "code",
"execution_count": 20,
"execution_count": 51,
"metadata": {},
"outputs": [
{
......@@ -714,7 +714,7 @@
},
{
"cell_type": "code",
"execution_count": 21,
"execution_count": 52,
"metadata": {},
"outputs": [
{
......
......@@ -2,8 +2,8 @@
# Authors: Pierre Fernbach <pfernbac@laas.fr>
import unittest
import curves
from curves import constant, constant3
import ndcurves as curves
from ndcurves import constant, constant3
import numpy as np
from numpy import array, isclose, array_equal
......
......@@ -2,8 +2,7 @@
# Authors: Pierre Fernbach <pfernbac@laas.fr>
import unittest
import curves
from curves import curve_constraints
from ndcurves import curve_constraints
import numpy as np
import pickle
from numpy import array, isclose, array_equal
......
......@@ -2,8 +2,8 @@
# Authors: Pierre Fernbach <pfernbac@laas.fr>
import unittest
import curves
from curves import polynomial
import ndcurves as curves
from ndcurves import polynomial
import numpy as np
from numpy import array, isclose, array_equal
......
......@@ -2,8 +2,8 @@
# Authors: Pierre Fernbach <pfernbac@laas.fr>
import unittest
import curves
from curves import sinusoidal
import ndcurves as curves
from ndcurves import sinusoidal
import numpy as np
from numpy import array, isclose, array_equal
......
......@@ -7,7 +7,7 @@ import numpy as np
from numpy import array, array_equal, isclose, random, zeros
from numpy.linalg import norm
import pickle
from curves import (CURVES_WITH_PINOCCHIO_SUPPORT, Quaternion, SE3Curve, SO3Linear, bezier, bezier3, convert_to_bezier,
from ndcurves import (CURVES_WITH_PINOCCHIO_SUPPORT, Quaternion, SE3Curve, SO3Linear, bezier, bezier3, convert_to_bezier,
convert_to_hermite, convert_to_polynomial, cubic_hermite_spline, curve_constraints, exact_cubic,
piecewise, piecewise_SE3, polynomial)
......
#include "curves/fwd.h"
#include "curves/exact_cubic.h"
#include "curves/bezier_curve.h"
#include "curves/polynomial.h"
#include "curves/helpers/effector_spline.h"
#include "curves/helpers/effector_spline_rotation.h"
#include "curves/curve_conversion.h"
#include "curves/cubic_hermite_spline.h"
#include "curves/piecewise_curve.h"
#include "curves/optimization/definitions.h"
#include "ndcurves/fwd.h"
#include "ndcurves/exact_cubic.h"
#include "ndcurves/bezier_curve.h"
#include "ndcurves/polynomial.h"
#include "ndcurves/helpers/effector_spline.h"
#include "ndcurves/helpers/effector_spline_rotation.h"
#include "ndcurves/curve_conversion.h"
#include "ndcurves/cubic_hermite_spline.h"
#include "ndcurves/piecewise_curve.h"
#include "ndcurves/optimization/definitions.h"
#include "load_problem.h"
#include "curves/so3_linear.h"
#include "curves/se3_curve.h"
#include "curves/serialization/curves.hpp"
#include "ndcurves/so3_linear.h"
#include "ndcurves/se3_curve.h"
#include "ndcurves/serialization/curves.hpp"
#include <string>
#include <iostream>
#include <cmath>
......@@ -20,7 +20,7 @@
using namespace std;
namespace curves {
namespace ndcurves {
typedef exact_cubic<double, double, true, Eigen::Matrix<double, 1, 1> > exact_cubic_one;
typedef exact_cubic_t::spline_constraints spline_constraints_t;
......@@ -41,9 +41,9 @@ bool QuasiEqual(const point3_t a, const point3_t b) {
}
return equal;
}
} // End namespace curves
} // End namespace ndcurves
using namespace curves;
using namespace ndcurves;
ostream& operator<<(ostream& os, const point3_t& pt) {
os << "(" << pt.x() << ", " << pt.y() << ", " << pt.z() << ")";
......@@ -526,7 +526,7 @@ void cubicConversionTest(bool& error) {
/*Exact Cubic Function tests*/
void ExactCubicNoErrorTest(bool& error) {
// Create an exact cubic spline with 7 waypoints => 6 polynomials defined in [0.0,3.0]
curves::T_Waypoint waypoints;
ndcurves::T_Waypoint waypoints;
for (double i = 0.0; i <= 3.0; i = i + 0.5) {
waypoints.push_back(std::make_pair(i, point3_t(i, i, i)));
}
......@@ -572,7 +572,7 @@ void ExactCubicNoErrorTest(bool& error) {
/*Exact Cubic Function tests*/
void ExactCubicTwoPointsTest(bool& error) {
// Create an exact cubic spline with 2 waypoints => 1 polynomial defined in [0.0,1.0]
curves::T_Waypoint waypoints;
ndcurves::T_Waypoint waypoints;
for (double i = 0.0; i < 2.0; ++i) {
waypoints.push_back(std::make_pair(i, point3_t(i, i, i)));
}
......@@ -596,7 +596,7 @@ void ExactCubicTwoPointsTest(bool& error) {
}
void ExactCubicOneDimTest(bool& error) {
curves::T_WaypointOne waypoints;
ndcurves::T_WaypointOne waypoints;
point_one zero;
zero(0, 0) = 9;
point_one one;
......@@ -615,7 +615,7 @@ void ExactCubicOneDimTest(bool& error) {
ComparePoints(one, res1, errmsg, error);
}
void CheckWayPointConstraint(const std::string& errmsg, const double step, const curves::T_Waypoint&,
void CheckWayPointConstraint(const std::string& errmsg, const double step, const ndcurves::T_Waypoint&,
const exact_cubic_t* curve, bool& error,
double prec = Eigen::NumTraits<double>::dummy_precision()) {
point3_t res1;
......@@ -626,7 +626,7 @@ void CheckWayPointConstraint(const std::string& errmsg, const double step, const
}
void ExactCubicPointsCrossedTest(bool& error) {
curves::T_Waypoint waypoints;
ndcurves::T_Waypoint waypoints;
for (double i = 0; i <= 1; i = i + 0.2) {
waypoints.push_back(std::make_pair(i, point3_t(i, i, i)));
}
......@@ -636,7 +636,7 @@ void ExactCubicPointsCrossedTest(bool& error) {
}
void ExactCubicVelocityConstraintsTest(bool& error) {
curves::T_Waypoint waypoints;
ndcurves::T_Waypoint waypoints;
for (double i = 0; i <= 1; i = i + 0.2) {
waypoints.push_back(std::make_pair(i, point3_t(i, i, i)));
}
......@@ -693,7 +693,7 @@ void CheckPointOnline(const std::string& errmsg, const point3_t& A, const point3
void EffectorTrajectoryTest(bool& error) {
// create arbitrary trajectory
curves::T_Waypoint waypoints;
ndcurves::T_Waypoint waypoints;
for (double i = 0; i <= 10; i = i + 2) {
waypoints.push_back(std::make_pair(i, point3_t(i, i, i)));
}
......@@ -741,7 +741,7 @@ double GetXRotFromQuat(helpers::quat_ref_const_t q) {
void EffectorSplineRotationNoRotationTest(bool& error) {
// create arbitrary trajectory
curves::T_Waypoint waypoints;
ndcurves::T_Waypoint waypoints;
for (double i = 0; i <= 10; i = i + 2) {
waypoints.push_back(std::make_pair(i, point3_t(i, i, i)));
}
......@@ -766,7 +766,7 @@ void EffectorSplineRotationNoRotationTest(bool& error) {
void EffectorSplineRotationRotationTest(bool& error) {
// create arbitrary trajectory
curves::T_Waypoint waypoints;
ndcurves::T_Waypoint waypoints;
for (double i = 0; i <= 10; i = i + 2) {
waypoints.push_back(std::make_pair(i, point3_t(i, i, i)));
}
......@@ -792,7 +792,7 @@ void EffectorSplineRotationRotationTest(bool& error) {
void EffectorSplineRotationWayPointRotationTest(bool& error) {
// create arbitrary trajectory
curves::T_Waypoint waypoints;
ndcurves::T_Waypoint waypoints;
for (double i = 0; i <= 10; i = i + 2) {
waypoints.push_back(std::make_pair(i, point3_t(i, i, i)));
}
......@@ -1363,7 +1363,7 @@ void curveAbcDimDynamicTest(bool& error) {
error = false;
}
// EXACT CUBIC : NOT SUPPORTED, problem to fix later
curves::T_Waypoint waypoints;
ndcurves::T_Waypoint waypoints;
for (double i = 0; i <= 1; i = i + 0.2) {
waypoints.push_back(std::make_pair(i, point3_t(i, i, i)));
}
......@@ -1652,7 +1652,7 @@ void serializationCurvesTest(bool& error) {
pchc_test.loadFromText<piecewise_t>(fileName);
CompareCurves<piecewise_t, piecewise_t>(ppc, pchc_test, errMsg4, error);
// Test serialization on exact cubic
curves::T_Waypoint waypoints;
ndcurves::T_Waypoint waypoints;
for (double i = 0; i <= 1; i = i + 0.2) {
waypoints.push_back(std::make_pair(i, point3_t(i, i, i)));
}
......@@ -2174,7 +2174,7 @@ void Se3serializationTest(bool& error) {
* @param error
*/
using namespace curves::optimization;
using namespace ndcurves::optimization;
var_pair_t setup_control_points(const std::size_t degree, const constraint_flag flag,
const point3_t& initPos = point3_t(), const point3_t& endPos = point3_t(),
......
......@@ -2,20 +2,20 @@
#ifndef _CLASS_LOAD_TEST_PROBLEMS
#define _CLASS_LOAD_TEST_PROBLEMS
#include "curves/exact_cubic.h"
#include "curves/bezier_curve.h"
#include "curves/helpers/effector_spline.h"
#include "curves/helpers/effector_spline_rotation.h"
#include "curves/optimization/quadratic_problem.h"
#include "curves/optimization/integral_cost.h"
#include "curves/optimization/details.h"
#include "ndcurves/exact_cubic.h"
#include "ndcurves/bezier_curve.h"
#include "ndcurves/helpers/effector_spline.h"
#include "ndcurves/helpers/effector_spline_rotation.h"
#include "ndcurves/optimization/quadratic_problem.h"
#include "ndcurves/optimization/integral_cost.h"
#include "ndcurves/optimization/details.h"
#include <iostream>
#include <fstream>
#include <string>
#include <stdlib.h>
namespace curves {
namespace ndcurves {
typedef Eigen::Vector3d point_t;
typedef std::vector<point_t, Eigen::aligned_allocator<point_t> > t_point_t;
......@@ -98,6 +98,6 @@ problem_definition_t loadproblem(const std::string& filename) {
}
} // namespace optimization
} // namespace curves
} // namespace ndcurves
#endif //_CLASS_LOAD_TEST_PROBLEMS
#define BOOST_TEST_MODULE test_constant
#include "curves/fwd.h"
#include "curves/constant_curve.h"
#include "curves/serialization/curves.hpp"
#include "ndcurves/fwd.h"
#include "ndcurves/constant_curve.h"
#include "ndcurves/serialization/curves.hpp"
#include <boost/test/included/unit_test.hpp>