polynomial.h
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2018, Alexander W. Winkler. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without
5 modification, are permitted provided that the following conditions are met:
6 
7 * Redistributions of source code must retain the above copyright notice, this
8  list of conditions and the following disclaimer.
9 
10 * Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 
14 * Neither the name of the copyright holder nor the names of its
15  contributors may be used to endorse or promote products derived from
16  this software without specific prior written permission.
17 
18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 ******************************************************************************/
29 
30 #ifndef TOWR_VARIABLES_POLYNOMIAL_H_
31 #define TOWR_VARIABLES_POLYNOMIAL_H_
32 
33 #include <string>
34 #include <vector>
35 
36 #include <Eigen/Dense>
37 
38 #include "state.h"
39 
40 namespace towr {
41 
53 class Polynomial {
54 public:
55  enum Coefficients { A=0, B, C, D, E, F, G, H, I, J};
56  using CoeffIDVec = std::vector<Coefficients>;
58 
59 public:
65  explicit Polynomial(int poly_order, int poly_dim);
66  virtual ~Polynomial() = default;
67 
71  State GetPoint(double t) const;
72 
80  double GetDerivativeWrtCoeff(double t, Dx poly_deriv, Coefficients coeff) const;
81 
82 protected:
83  std::vector<VectorXd> coeff_;
84 
85 private:
87 };
88 
89 
106 public:
107  CubicHermitePolynomial(int dim);
108  virtual ~CubicHermitePolynomial() = default;
109 
110 
114  void SetDuration(double duration);
115 
121  void SetNodes(const Node& n0, const Node& n1);
122 
126  void UpdateCoeff();
127 
132  VectorXd GetDerivativeOfPosWrtDuration(double t) const;
133 
140  double GetDerivativeWrtStartNode(Dx dfdt, Dx node_deriv, double t) const;
141 
148  double GetDerivativeWrtEndNode(Dx dfdt, Dx node_deriv, double t) const;
149 
153  const double GetDuration() const { return T_; };
154 
155 private:
156  double T_;
157  Node n0_, n1_;
158 
159  // see matlab/cubic_hermite_polynomial.m script for derivation
160  double GetDerivativeOfPosWrtStartNode(Dx node_deriv, double t_local) const;
161  double GetDerivativeOfVelWrtStartNode(Dx node_deriv, double t_local) const;
162  double GetDerivativeOfAccWrtStartNode(Dx node_deriv, double t_local) const;
163 
164  double GetDerivativeOfPosWrtEndNode(Dx node_deriv, double t_local) const;
165  double GetDerivativeOfVelWrtEndNode(Dx node_deriv, double t_local) const;
166  double GetDerivativeOfAccWrtEndNode(Dx node_deriv, double t_local) const;
167 };
168 
169 } // namespace towr
170 
171 #endif // TOWR_VARIABLES_POLYNOMIAL_H_
Stores at state comprised of values and higher-order derivatives.
Definition: state.h:49
A polynomial of arbitrary order and dimension.
Definition: polynomial.h:53
double T_
the total duration of the polynomial.
Definition: polynomial.h:153
std::vector< Coefficients > CoeffIDVec
Definition: polynomial.h:56
Eigen::VectorXd VectorXd
Node n1_
the start and final node comprising the polynomial.
Definition: polynomial.h:157
CoeffIDVec coeff_ids_
Definition: polynomial.h:86
Polynomial(int poly_order, int poly_dim)
Constructs a polynomial with zero coefficient values.
Definition: polynomial.cc:38
Eigen::VectorXd VectorXd
Definition: polynomial.h:57
double GetDerivativeWrtCoeff(double t, Dx poly_deriv, Coefficients coeff) const
The derivative of the polynomial with respect to the coefficients.
Definition: polynomial.cc:64
std::vector< VectorXd > coeff_
Definition: polynomial.h:83
virtual ~Polynomial()=default
Represents a Cubic-Hermite-Polynomial.
Definition: polynomial.h:105
State GetPoint(double t) const
Definition: polynomial.cc:47
A node represents the state of a trajectory at a specific time.
Definition: state.h:107
Dx
< the values or derivative. For motions e.g. position, velocity, ...
Definition: state.h:41


towr_core
Author(s): Alexander W. Winkler
autogenerated on Sun Apr 8 2018 02:18:53