hpp-spline  4.10.0
template based classes for creating and manipulating spline and bezier curves. Comes with extra options specific to end-effector trajectories in robotics.
curve_constraint.h
Go to the documentation of this file.
1 
11 #ifndef _CLASS_CURVE_CONSTRAINT
12 #define _CLASS_CURVE_CONSTRAINT
13 
14 #include "MathDefs.h"
15 
16 #include <functional>
17 #include <vector>
18 
19 namespace spline {
20 template <typename Point>
22  typedef Point point_t;
24 
26  point_t init_vel;
27  point_t init_acc;
28  point_t end_vel;
29  point_t end_acc;
30 };
31 } // namespace spline
32 #endif //_CLASS_CUBICZEROVELACC
Definition: curve_constraint.h:21
Definition: bernstein.h:20
curve_constraints()
Definition: curve_constraint.h:23
point_t init_vel
Definition: curve_constraint.h:26
point_t end_acc
Definition: curve_constraint.h:29
Point point_t
Definition: curve_constraint.h:22
point_t init_acc
Definition: curve_constraint.h:27
point_t end_vel
Definition: curve_constraint.h:28
~curve_constraints()
Definition: curve_constraint.h:25
Eigen::Matrix< Numeric, 3, 1 > Point
Definition: effector_spline.h:28