dynamic_constraint.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_CONSTRAINTS_DYNAMIC_CONSTRAINT_H_
31 #define TOWR_CONSTRAINTS_DYNAMIC_CONSTRAINT_H_
32 
33 #include <towr/variables/spline.h>
36 
38 #include <towr/parameters.h>
39 
41 
42 namespace towr {
43 
61 public:
62  using Vector6d = Eigen::Matrix<double, 6, 1>;
63 
71  const Parameters& params,
72  const SplineHolder& spline_holder);
73  virtual ~DynamicConstraint () = default;
74 
75 private:
78  std::vector<NodeSpline::Ptr> ee_forces_;
79  std::vector<NodeSpline::Ptr> ee_motion_;
80 
82 
89  int GetRow(int k, Dim6D dimension) const;
90 
95  void UpdateModel(double t) const;
96 
97  virtual void UpdateConstraintAtInstance(double t, int k, VectorXd& g) const override;
98  virtual void UpdateBoundsAtInstance(double t, int k, VecBound& bounds) const override;
99  virtual void UpdateJacobianAtInstance(double t, int k, std::string, Jacobian&) const override;
100 };
101 
102 } /* namespace towr */
103 
104 #endif /* TOWR_CONSTRAINTS_DYNAMIC_CONSTRAINT_H_ */
DynamicConstraint(const DynamicModel::Ptr &model, const Parameters &params, const SplineHolder &spline_holder)
Construct a Dynamic constraint.
Ensure that the optimized motion complies with the system dynamics.
Eigen::Matrix< double, 6, 1 > Vector6d
Constraints evaluated at discretized times along a trajectory.
std::shared_ptr< NodeSpline > Ptr
Definition: node_spline.h:52
void UpdateModel(double t) const
Updates the model with the current state and forces.
virtual void UpdateConstraintAtInstance(double t, int k, VectorXd &g) const override
Sets the constraint value a specific time t, corresponding to node k.
EulerConverter base_angular_
angular base state
NodeSpline::Ptr base_linear_
lin. base pos/vel/acc in world frame
Eigen::VectorXd VectorXd
virtual void UpdateJacobianAtInstance(double t, int k, std::string, Jacobian &) const override
Sets Jacobian rows at a specific time t, corresponding to node k.
Holds pointers to fully constructed splines, that are linked to the optimization variables.
Definition: spline_holder.h:46
Converts Euler angles and derivatives to angular quantities.
std::shared_ptr< DynamicModel > Ptr
Definition: dynamic_model.h:60
std::vector< NodeSpline::Ptr > ee_forces_
endeffector forces in world frame.
virtual void UpdateBoundsAtInstance(double t, int k, VecBound &bounds) const override
Sets upper/lower bound a specific time t, corresponding to node k.
std::vector< NodeSpline::Ptr > ee_motion_
endeffector position in world frame.
Holds the parameters to tune the optimization problem.
Definition: parameters.h:45
DynamicModel::Ptr model_
the dynamic model (e.g. Centroidal)
virtual ~DynamicConstraint()=default
int GetRow(int k, Dim6D dimension) const
The row in the overall constraint for this evaluation time.


towr_core
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 7 2018 02:15:57