Keeps the 6D base motion in a specified range. More...
#include <base_motion_constraint.h>
Public Member Functions | |
BaseMotionConstraint (const Parameters ¶ms, 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... | |
virtual 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 |
Public Member Functions inherited from towr::TimeDiscretizationConstraint | |
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 |
Private Member Functions | |
int | GetRow (int node, int dim) const |
Private Attributes | |
NodeSpline::Ptr | base_angular_ |
NodeSpline::Ptr | base_linear_ |
VecBound | node_bounds_ |
same bounds for each discretized node More... | |
Additional Inherited Members | |
Public Types inherited from towr::TimeDiscretizationConstraint | |
using | Bounds = ifopt::Bounds |
using | VecTimes = std::vector< double > |
Protected Member Functions inherited from towr::TimeDiscretizationConstraint | |
int | GetNumberOfNodes () const |
Protected Attributes inherited from towr::TimeDiscretizationConstraint | |
VecTimes | dts_ |
times at which the constraint is evaluated. More... | |
Keeps the 6D base motion in a specified range.
In general this constraint should be avoided, since a similar affect can be achieved with RangeOfMotion.
Definition at line 47 of file base_motion_constraint.h.
towr::BaseMotionConstraint::BaseMotionConstraint | ( | const Parameters & | params, |
const SplineHolder & | spline_holder | ||
) |
Links the base variables and sets hardcoded bounds on the state.
params | The variables describing the optimization problem. |
spline_holder | Holds pointers to the base variables. |
Definition at line 38 of file base_motion_constraint.cc.
|
virtualdefault |
|
private |
Definition at line 90 of file base_motion_constraint.cc.
|
overridevirtual |
Sets upper/lower bound a specific time t, corresponding to node k.
t | The time along the trajectory to set the bounds. |
k | The index of the time t, so t=k*dt |
Implements towr::TimeDiscretizationConstraint.
Definition at line 71 of file base_motion_constraint.cc.
|
overridevirtual |
Sets the constraint value a specific time t, corresponding to node k.
t | The time along the trajectory to set the constraint. |
k | The index of the time t, so t=k*dt |
Implements towr::TimeDiscretizationConstraint.
Definition at line 63 of file base_motion_constraint.cc.
|
overridevirtual |
Sets Jacobian rows at a specific time t, corresponding to node k.
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 78 of file base_motion_constraint.cc.
|
private |
Definition at line 65 of file base_motion_constraint.h.
|
private |
Definition at line 64 of file base_motion_constraint.h.
|
private |
same bounds for each discretized node
Definition at line 67 of file base_motion_constraint.h.