fwd.h
Go to the documentation of this file.
1 
10 #ifndef CURVES_FWD_H
11 #define CURVES_FWD_H
12 #include <Eigen/Dense>
13 #include <boost/smart_ptr/shared_ptr.hpp>
14 #include <vector>
15 
16 namespace ndcurves {
17 
18 template <typename Time, typename Numeric, bool Safe, typename Point,
19  typename Point_derivate>
20 struct curve_abc;
21 
22 template <typename Time, typename Numeric, bool Safe, typename Point>
23 struct bezier_curve;
24 
25 template <typename Time, typename Numeric, bool Safe, typename Point,
26  typename Point_derivate>
27 struct constant_curve;
28 
29 template <typename Time, typename Numeric, bool Safe, typename Point>
30 struct cubic_hermite_spline;
31 
32 template <typename Time, typename Numeric, bool Safe, typename Point,
33  typename T_Point, typename SplineBase>
34 struct exact_cubic;
35 
36 template <typename Time, typename Numeric, bool Safe, typename Point,
37  typename Point_derivate, typename CurveType>
38 struct piecewise_curve;
39 
40 template <typename Time, typename Numeric, bool Safe, typename Point,
41  typename T_Point>
42 struct polynomial;
43 
44 template <typename Time, typename Numeric, bool Safe>
45 struct SE3Curve;
46 
47 template <typename Time, typename Numeric, bool Safe, typename Point>
48 struct sinusoidal;
49 
50 template <typename Time, typename Numeric, bool Safe>
51 struct SO3Linear;
52 
53 template <typename Numeric>
54 struct Bern;
55 
56 template <typename Point>
57 struct curve_constraints;
58 
59 template <typename Numeric, bool Safe>
60 struct linear_variable;
61 
62 template <typename Numeric>
63 struct quadratic_variable;
64 
65 // typedef of the commonly used templates arguments :
66 // eigen types :
67 typedef Eigen::Vector3d point3_t;
68 typedef Eigen::Matrix<double, 6, 1> point6_t;
69 typedef Eigen::VectorXd pointX_t;
70 typedef Eigen::Matrix<double, 3, 3> matrix3_t;
71 typedef Eigen::Matrix<double, 4, 4> matrix4_t;
72 typedef Eigen::Quaternion<double> quaternion_t;
73 typedef Eigen::Transform<double, 3, Eigen::Affine> transform_t;
74 typedef std::vector<point3_t, Eigen::aligned_allocator<point3_t> > t_point3_t;
75 typedef std::vector<pointX_t, Eigen::aligned_allocator<pointX_t> > t_pointX_t;
76 
77 // abstract curves types:
79  curve_abc_t; // base abstract class
81  curve_3_t; // generic class of curve of size 3
83  curve_rotation_t; // templated class used for the rotation (return
84  // dimension are fixed)
86  curve_SE3_t; // templated abstract class used for all the se3 curves
87  // (return dimension are fixed)
88 
89 // shared pointer to abstract types:
90 typedef boost::shared_ptr<curve_abc_t> curve_ptr_t;
91 typedef boost::shared_ptr<curve_3_t> curve3_ptr_t;
92 typedef boost::shared_ptr<curve_rotation_t> curve_rotation_ptr_t;
93 typedef boost::shared_ptr<curve_SE3_t> curve_SE3_ptr_t;
94 
95 // definition of all curves class with pointX as return type:
109 
110 // definition of all curves class with point3 as return type:
120 
121 // special curves with return type fixed:
124 typedef piecewise_curve<double, double, true, transform_t, point6_t,
125  curve_SE3_t>
127 
128 } // namespace ndcurves
129 
130 #endif // CURVES_FWD_H
Eigen::Matrix< Numeric, Eigen::Dynamic, 1 > Point
Definition: effector_spline.h:28
double Numeric
Definition: effector_spline.h:26
double Time
Definition: effector_spline.h:27
std::vector< Point, Eigen::aligned_allocator< Point > > T_Point
Definition: effector_spline.h:29
Definition: bernstein.h:20
bezier_curve< double, double, true, pointX_t > bezier_t
Definition: fwd.h:99
std::vector< pointX_t, Eigen::aligned_allocator< pointX_t > > t_pointX_t
Definition: fwd.h:75
curve_abc< double, double, true, point3_t, point3_t > curve_3_t
Definition: fwd.h:81
curve_abc< double, double, true, transform_t, point6_t > curve_SE3_t
Definition: fwd.h:86
curve_abc< double, double, true, pointX_t, pointX_t > curve_abc_t
Definition: fwd.h:79
piecewise_curve< double, double, true, transform_t, point6_t, curve_SE3_t > piecewise_SE3_t
Definition: fwd.h:126
Eigen::Vector3d point3_t
Definition: fwd.h:63
Eigen::Quaternion< double > quaternion_t
Definition: fwd.h:72
std::vector< point3_t, Eigen::aligned_allocator< point3_t > > t_point3_t
Definition: fwd.h:74
SO3Linear< double, double, true > SO3Linear_t
Definition: fwd.h:122
SE3Curve< double, double, true > SE3Curve_t
Definition: fwd.h:123
exact_cubic< double, double, true, point3_t, t_point3_t, polynomial_t > exact_cubic3_t
Definition: fwd.h:113
polynomial< double, double, true, point3_t, t_point3_t > polynomial3_t
Definition: fwd.h:111
sinusoidal< double, double, true, pointX_t > sinusoidal_t
Definition: fwd.h:108
constant_curve< double, double, true, point3_t, point3_t > constant3_t
Definition: fwd.h:115
exact_cubic< double, double, true, pointX_t, t_pointX_t, polynomial_t > exact_cubic_t
Definition: fwd.h:98
boost::shared_ptr< curve_SE3_t > curve_SE3_ptr_t
Definition: fwd.h:93
Eigen::VectorXd pointX_t
Definition: fwd.h:69
Eigen::Transform< double, 3, Eigen::Affine > transform_t
Definition: fwd.h:73
piecewise_curve< double, double, true, point3_t, point3_t, curve_3_t > piecewise3_t
Definition: fwd.h:119
bezier_curve< double, double, true, point3_t > bezier3_t
Definition: fwd.h:114
Eigen::Matrix< double, 3, 3 > matrix3_t
Definition: fwd.h:70
bezier_curve< double, double, true, linear_variable_t > bezier_linear_variable_t
Definition: fwd.h:102
Eigen::Matrix< double, 6, 1 > point6_t
Definition: fwd.h:68
cubic_hermite_spline< double, double, true, pointX_t > cubic_hermite_spline_t
Definition: fwd.h:105
boost::shared_ptr< curve_rotation_t > curve_rotation_ptr_t
Definition: fwd.h:92
curve_abc< double, double, true, matrix3_t, point3_t > curve_rotation_t
Definition: fwd.h:83
Eigen::Matrix< double, 4, 4 > matrix4_t
Definition: fwd.h:71
boost::shared_ptr< curve_abc_t > curve_ptr_t
Definition: fwd.h:90
boost::shared_ptr< curve_3_t > curve3_ptr_t
Definition: fwd.h:91
cubic_hermite_spline< double, double, true, point3_t > cubic_hermite_spline3_t
Definition: fwd.h:117
polynomial< double, double, true, pointX_t, t_pointX_t > polynomial_t
Definition: fwd.h:96
piecewise_curve< double, double, true, pointX_t, pointX_t, curve_abc_t > piecewise_t
Definition: fwd.h:107
constant_curve< double, double, true, pointX_t, pointX_t > constant_t
Definition: fwd.h:103
linear_variable< double, true > linear_variable_t
Definition: fwd.h:100
Definition: fwd.h:54
Composition of a curve of any type of dimension 3 and a curve representing an rotation (in current im...
Definition: se3_curve.h:26
Represents a linear interpolation in SO3, using the slerp method provided by Eigen::Quaternion.
Definition: so3_linear.h:21
Definition: bezier_curve.h:31
Represents a constant_curve curve, always returning the same value and a null derivative.
Definition: constant_curve.h:23
Definition: cubic_hermite_spline.h:34
Represents a curve of dimension Dim. If value of parameter Safe is false, no verification is made on ...
Definition: curve_abc.h:37
Definition: curve_constraint.h:20
Definition: exact_cubic.h:41
Definition: linear_variable.h:26
Definition: piecewise_curve.h:37
Represents a polynomial of an arbitrary order defined on the interval . It follows the equation : ...
Definition: polynomial.h:35
Definition: quadratic_variable.h:25
Represents a sinusoidal curve, evaluating the following equation: p0 + amplitude * (sin(2pi/T + phi)
Definition: sinusoidal.h:23