8 #ifndef _CLASS_CUBICHERMITESPLINE 9 #define _CLASS_CUBICHERMITESPLINE 11 #include <boost/serialization/utility.hpp> 32 template <
typename Time = double,
typename Numeric =
Time,
bool Safe =
false,
33 typename Point = Eigen::Matrix<Numeric, Eigen::Dynamic, 1> >
37 typedef std::vector<pair_point_tangent_t, Eigen::aligned_allocator<Point> >
62 template <
typename In>
65 :
size_(std::distance(PairsBegin, PairsEnd)),
degree_(3) {
67 if (Safe &&
size_ < 1) {
68 throw std::length_error(
69 "can not create cubic_hermite_spline, number of pairs is inferior to " 73 dim_ = PairsBegin->first.size();
76 for (; it != PairsEnd; ++it) {
77 if (Safe && (static_cast<size_t>(it->first.size()) !=
dim_ ||
78 static_cast<size_t>(it->second.size()) !=
dim_))
79 throw std::invalid_argument(
80 "All the control points and their derivatives must have the same " 110 throw std::invalid_argument(
111 "can't evaluate cubic hermite spline, out of range");
116 const bezier_t bezier = buildCurrentBezier(t);
132 const Numeric prec = Eigen::NumTraits<Numeric>::dummy_precision())
const {
133 bool equal = ndcurves::isApprox<num_t>(
T_min_, other.
min()) &&
134 ndcurves::isApprox<num_t>(
T_max_, other.
max()) &&
139 if (!equal)
return false;
140 for (std::size_t i = 0; i <
size_; ++i) {
152 const Numeric prec = Eigen::NumTraits<Numeric>::dummy_precision())
const {
166 return !(*
this == other);
178 throw std::invalid_argument(
179 "can't derivate cubic hermite spline, out of range");
184 const bezier_t bezier = buildCurrentBezier(t);
191 for (
size_t i = 0; i <
size_ - 1; ++i) {
216 if (time_control_points.size() !=
size()) {
217 throw std::length_error(
218 "size of time control points should be equal to number of control " 221 computeDurationSplines();
222 if (!checkDurationSplines()) {
223 throw std::invalid_argument(
224 "time_splines not monotonous, all spline duration should be superior " 254 std::size_t findInterval(
const time_t t)
const {
263 std::size_t left_id = 0;
264 std::size_t right_id =
size_ - 1;
265 while (left_id <= right_id) {
266 const std::size_t middle_id = left_id + (right_id - left_id) / 2;
268 left_id = middle_id + 1;
270 right_id = middle_id - 1;
286 size_t id_interval = findInterval(t);
292 control_points.reserve(4);
293 control_points.push_back(pair0.first);
294 control_points.push_back(pair0.first + pair0.second / 3. * (t1 - t0));
295 control_points.push_back(pair1.first - pair1.second / 3. * (t1 - t0));
296 control_points.push_back(pair1.first);
297 return bezier_t(control_points.begin(), control_points.end(), t0, t1);
303 void check_conditions()
const {
305 throw std::runtime_error(
306 "Error in cubic hermite : there is no control points set / did you " 307 "use empty constructor ?");
308 }
else if (
dim_ == 0) {
309 throw std::runtime_error(
310 "Error in cubic hermite : Dimension of points is zero / did you use " 311 "empty constructor ?");
320 void computeDurationSplines() {
325 for (i = 0; i <
size() - 1; i++) {
328 prev_time = actual_time;
335 bool checkDurationSplines()
const {
337 bool is_positive =
true;
350 std::size_t
virtual dim()
const {
return dim_; }
393 template <
class Archive>
394 void serialize(Archive& ar,
const unsigned int version) {
398 ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(
curve_abc_t);
399 ar& boost::serialization::make_nvp(
"dim",
dim_);
401 ar& boost::serialization::make_nvp(
"time_control_points",
404 ar& boost::serialization::make_nvp(
"T_min",
T_min_);
405 ar& boost::serialization::make_nvp(
"T_max",
T_max_);
406 ar& boost::serialization::make_nvp(
"size",
size_);
407 ar& boost::serialization::make_nvp(
"degree",
degree_);
415 #endif //_CLASS_CUBICHERMITESPLINE #define SINGLE_ARG(...)
Definition: archive.hpp:23
Definition: bernstein.h:20
virtual bool isApprox(const curve_abc_t *other, const Numeric prec=Eigen::NumTraits< Numeric >::dummy_precision()) const
Definition: cubic_hermite_spline.h:150
virtual point_t derivate(const time_t t, const std::size_t order) const
Evaluate the derivative order N of curve at time t. If derivative is to be evaluated several times...
Definition: bezier_curve.h:308
t_pair_point_tangent_t control_points_
Vector of pair < Point, Tangent >.
Definition: cubic_hermite_spline.h:366
bezier_curve_t compute_derivate(const std::size_t order) const
Compute the derived curve at order N. Computes the derivative order N, of bezier curve of parametric...
Definition: bezier_curve.h:206
Numeric num_t
Definition: cubic_hermite_spline.h:41
vector_time_t duration_splines_
Definition: cubic_hermite_spline.h:377
virtual Time max() const
Get the maximum time for which the curve is defined.
Definition: cubic_hermite_spline.h:356
friend class boost::serialization::access
Definition: cubic_hermite_spline.h:391
virtual Time min() const
Get the minimum time for which the curve is defined.
Definition: cubic_hermite_spline.h:353
Definition: cubic_hermite_spline.h:34
Time T_max_
Definition: cubic_hermite_spline.h:383
bezier_curve< Time, Numeric, Safe, point_t > bezier_t
Definition: cubic_hermite_spline.h:45
virtual Point derivate(const time_t t, const std::size_t order) const
Evaluate the derivative of order N of spline at time t.
Definition: cubic_hermite_spline.h:175
cubic_hermite_spline< Time, Numeric, Safe, point_t > cubic_hermite_spline_t
Definition: cubic_hermite_spline.h:44
std::size_t size() const
Get number of control points contained in the trajectory.
Definition: cubic_hermite_spline.h:242
interface for a Curve of arbitrary dimension.
Time time_t
Definition: cubic_hermite_spline.h:40
piecewise_curve< Time, Numeric, Safe, point_t, point_t, bezier_t > piecewise_bezier_t
Definition: cubic_hermite_spline.h:48
t_pair_point_tangent_t getControlPoints()
Get vector of pair (positition, derivative) corresponding to control points.
Definition: cubic_hermite_spline.h:232
class allowing to create a Bezier curve of dimension 1 <= n <= 3.
std::vector< point_t, Eigen::aligned_allocator< point_t > > t_point_t
Definition: bezier_curve.h:38
std::vector< Time > vector_time_t
Definition: cubic_hermite_spline.h:39
virtual std::size_t dim() const
Get dimension of curve.
Definition: cubic_hermite_spline.h:350
virtual std::size_t degree() const
Get the degree of the curve.
Definition: cubic_hermite_spline.h:359
std::size_t degree_
Degree (Cubic so degree 3)
Definition: cubic_hermite_spline.h:387
double Time
Definition: effector_spline.h:27
cubic_hermite_spline(In PairsBegin, In PairsEnd, const vector_time_t &time_control_points)
Constructor.
Definition: cubic_hermite_spline.h:63
piecewise_bezier_t compute_derivate(const std::size_t order) const
Definition: cubic_hermite_spline.h:189
virtual bool operator!=(const cubic_hermite_spline_t &other) const
Definition: cubic_hermite_spline.h:165
Time T_min_
Definition: cubic_hermite_spline.h:380
virtual ~cubic_hermite_spline()
Destructor.
Definition: cubic_hermite_spline.h:99
#define DEFINE_CLASS_TEMPLATE_VERSION(Template, Type)
Definition: archive.hpp:27
cubic_hermite_spline()
Empty constructor. Curve obtained this way can not perform other class functions. ...
Definition: cubic_hermite_spline.h:54
cubic_hermite_spline(const cubic_hermite_spline &other)
Definition: cubic_hermite_spline.h:88
std::size_t size_
Number of control points (pairs).
Definition: cubic_hermite_spline.h:385
Eigen::Matrix< Numeric, Eigen::Dynamic, 1 > Point
Definition: effector_spline.h:28
Definition: bezier_curve.h:31
std::size_t numIntervals() const
Get number of intervals (subsplines) contained in the trajectory.
Definition: cubic_hermite_spline.h:247
std::pair< Point, Point > pair_point_tangent_t
Definition: cubic_hermite_spline.h:36
std::vector< pair_point_tangent_t, Eigen::aligned_allocator< Point > > t_pair_point_tangent_t
Definition: cubic_hermite_spline.h:38
bool isApprox(const cubic_hermite_spline_t &other, const Numeric prec=Eigen::NumTraits< Numeric >::dummy_precision()) const
isApprox check if other and *this are approximately equals. Only two curves of the same class can be ...
Definition: cubic_hermite_spline.h:130
double Numeric
Definition: effector_spline.h:26
class allowing to create a piecewise curve.
virtual bool operator==(const cubic_hermite_spline_t &other) const
Definition: cubic_hermite_spline.h:161
void add_curve(const Curve &curve)
Definition: piecewise_curve.h:176
std::size_t dim_
Dim of curve.
Definition: cubic_hermite_spline.h:364
virtual Point operator()(const time_t t) const
Evaluation of the cubic hermite spline at time t.
Definition: cubic_hermite_spline.h:107
void setTime(const vector_time_t &time_control_points)
Set time of each control point of cubic hermite spline. Set duration of each spline, Exemple : with values corresponding to times for respectively.
Definition: cubic_hermite_spline.h:212
void serialize(Archive &ar, const unsigned int version)
Definition: cubic_hermite_spline.h:394
vector_time_t getTime()
Get vector of Time corresponding to Time for each control point.
Definition: cubic_hermite_spline.h:237
piecewise_bezier_t * compute_derivate_ptr(const std::size_t order) const
Compute the derived curve at order N.
Definition: cubic_hermite_spline.h:202
Point point_t
Definition: cubic_hermite_spline.h:35
curve_abc< Time, Numeric, Safe, point_t > curve_abc_t
Definition: cubic_hermite_spline.h:42
Represents a curve of dimension Dim. If value of parameter Safe is false, no verification is made on ...
Definition: curve_abc.h:37
bezier_t::t_point_t t_point_t
Definition: cubic_hermite_spline.h:46
vector_time_t time_control_points_
Definition: cubic_hermite_spline.h:371