Keeps the 6D base motion in a specified range.
More...
#include <base_motion_constraint.h>
|
| | BaseMotionConstraint (double T, double dt, const SplineHolder &spline_holder) |
| | Links the base variables and sets hardcoded bounds on the state. More...
|
| |
| void | UpdateBoundsAtInstance (double t, int k, VecBound &) const override |
| | Sets upper/lower bound a specific time t, corresponding to node k. More...
|
| |
| void | UpdateConstraintAtInstance (double t, int k, VectorXd &g) const override |
| | Sets the constraint value a specific time t, corresponding to node k. More...
|
| |
| void | UpdateJacobianAtInstance (double t, int k, std::string, Jacobian &) const override |
| | Sets Jacobian rows at a specific time t, corresponding to node k. More...
|
| |
| virtual | ~BaseMotionConstraint ()=default |
| |
| void | FillJacobianBlock (std::string var_set, Jacobian &) const override |
| |
| VecBound | GetBounds () const override |
| |
| Eigen::VectorXd | GetValues () const override |
| |
| | TimeDiscretizationConstraint (double T, double dt, std::string constraint_name) |
| | Constructs a constraint for ifopt. More...
|
| |
| | TimeDiscretizationConstraint (const VecTimes &dts, std::string name) |
| | construct a constraint for ifopt. More...
|
| |
| virtual | ~TimeDiscretizationConstraint ()=default |
| |
| | ConstraintSet (int n_constraints, const std::string &name) |
| |
| Jacobian | GetJacobian () const final |
| |
| void | LinkWithVariables (const VariablesPtr &x) |
| |
| virtual | ~ConstraintSet ()=default |
| |
| | Component (int num_rows, const std::string &name) |
| |
| std::string | GetName () const |
| |
| int | GetRows () const |
| |
| virtual void | Print (double tolerance, int &index_start) const |
| |
| void | SetRows (int num_rows) |
| |
| virtual | ~Component ()=default |
| |
|
| int | GetRow (int node, int dim) const |
| |
Keeps the 6D base motion in a specified range.
In general this constraint should be avoided, since a similar affect can be achieved with RangeOfMotionConstraint.
Definition at line 48 of file base_motion_constraint.h.
◆ BaseMotionConstraint()
| towr::BaseMotionConstraint::BaseMotionConstraint |
( |
double |
T, |
|
|
double |
dt, |
|
|
const SplineHolder & |
spline_holder |
|
) |
| |
Links the base variables and sets hardcoded bounds on the state.
- Parameters
-
| T | The total time of the optimization horizon. |
| dt | The discretization interval of the constraints. |
| spline_holder | Holds pointers to the base variables. |
Definition at line 38 of file base_motion_constraint.cc.
◆ ~BaseMotionConstraint()
| virtual towr::BaseMotionConstraint::~BaseMotionConstraint |
( |
| ) |
|
|
virtualdefault |
◆ GetRow()
| int towr::BaseMotionConstraint::GetRow |
( |
int |
node, |
|
|
int |
dim |
|
) |
| const |
|
private |
◆ UpdateBoundsAtInstance()
| void towr::BaseMotionConstraint::UpdateBoundsAtInstance |
( |
double |
t, |
|
|
int |
k, |
|
|
VecBound & |
b |
|
) |
| const |
|
overridevirtual |
◆ UpdateConstraintAtInstance()
| void towr::BaseMotionConstraint::UpdateConstraintAtInstance |
( |
double |
t, |
|
|
int |
k, |
|
|
VectorXd & |
g |
|
) |
| const |
|
overridevirtual |
◆ UpdateJacobianAtInstance()
| void towr::BaseMotionConstraint::UpdateJacobianAtInstance |
( |
double |
t, |
|
|
int |
k, |
|
|
std::string |
var_set, |
|
|
Jacobian & |
jac |
|
) |
| const |
|
overridevirtual |
Sets Jacobian rows at a specific time t, corresponding to node k.
- Parameters
-
| t | The time along the trajcetory to set the bounds. |
| k | The index of the time t, so t=k*dt |
| var_set | The name of the ifopt variables currently being queried for. |
| |
Implements towr::TimeDiscretizationConstraint.
Definition at line 76 of file base_motion_constraint.cc.
◆ base_angular_
◆ base_linear_
◆ node_bounds_
| VecBound towr::BaseMotionConstraint::node_bounds_ |
|
private |
The documentation for this class was generated from the following files: