Public Member Functions | Private Member Functions | Private Attributes
towr::BaseMotionConstraint Class Reference

Keeps the 6D base motion in a specified range. More...

#include <base_motion_constraint.h>

Inheritance diagram for towr::BaseMotionConstraint:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 BaseMotionConstraint (const Parameters &params, const SplineHolder &spline_holder)
 Links the base variables and sets hardcoded bounds on the state.
void UpdateBoundsAtInstance (double t, int k, VecBound &) const override
 Sets upper/lower bound a specific time t, corresponding to node k.
void UpdateConstraintAtInstance (double t, int k, VectorXd &g) const override
 Sets the constraint value a specific time t, corresponding to node k.
virtual void UpdateJacobianAtInstance (double t, int k, std::string, Jacobian &) const override
 Sets Jacobian rows at a specific time t, corresponding to node k.
virtual ~BaseMotionConstraint ()

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

Detailed Description

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.


Constructor & Destructor Documentation

towr::BaseMotionConstraint::BaseMotionConstraint ( const Parameters params,
const SplineHolder spline_holder 
)

Links the base variables and sets hardcoded bounds on the state.

Parameters:
paramsThe variables describing the optimization problem.
spline_holderHolds pointers to the base variables.

Definition at line 38 of file base_motion_constraint.cc.


Member Function Documentation

int towr::BaseMotionConstraint::GetRow ( int  node,
int  dim 
) const [private]

Definition at line 90 of file base_motion_constraint.cc.

void towr::BaseMotionConstraint::UpdateBoundsAtInstance ( double  t,
int  k,
VecBound &  b 
) const [override, virtual]

Sets upper/lower bound a specific time t, corresponding to node k.

Parameters:
tThe time along the trajectory to set the bounds.
kThe index of the time t, so t=k*dt
in/out]b The complete vector of bounds, for which the corresponding row must be set.

Implements towr::TimeDiscretizationConstraint.

Definition at line 71 of file base_motion_constraint.cc.

void towr::BaseMotionConstraint::UpdateConstraintAtInstance ( double  t,
int  k,
VectorXd &  g 
) const [override, virtual]

Sets the constraint value a specific time t, corresponding to node k.

Parameters:
tThe time along the trajectory to set the constraint.
kThe index of the time t, so t=k*dt
in/out]g The complete vector of constraint values, for which the corresponding row must be filled.

Implements towr::TimeDiscretizationConstraint.

Definition at line 63 of file base_motion_constraint.cc.

void towr::BaseMotionConstraint::UpdateJacobianAtInstance ( double  t,
int  k,
std::string  var_set,
Jacobian &  jac 
) const [override, virtual]

Sets Jacobian rows at a specific time t, corresponding to node k.

Parameters:
tThe time along the trajcetory to set the bounds.
kThe index of the time t, so t=k*dt
var_setThe name of the ifopt variables currently being queried for.
in/out]jac The complete Jacobian, for which the corresponding row and columns must be set.

Implements towr::TimeDiscretizationConstraint.

Definition at line 78 of file base_motion_constraint.cc.


Member Data Documentation

NodeSpline::Ptr towr::BaseMotionConstraint::base_angular_ [private]

Definition at line 65 of file base_motion_constraint.h.

NodeSpline::Ptr towr::BaseMotionConstraint::base_linear_ [private]

Definition at line 64 of file base_motion_constraint.h.

same bounds for each discretized node

Definition at line 67 of file base_motion_constraint.h.


The documentation for this class was generated from the following files:


towr_core
Author(s): Alexander W. Winkler
autogenerated on Mon Apr 9 2018 03:12:44