Public Member Functions | Private Member Functions | Private Attributes | List of all members
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]

Public Member Functions

 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
 
- 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
 
- Public Member Functions inherited from ifopt::ConstraintSet
 ConstraintSet (int n_constraints, const std::string &name)
 
Jacobian GetJacobian () const final
 
void LinkWithVariables (const VariablesPtr &x)
 
virtual ~ConstraintSet ()=default
 
- Public Member Functions inherited from ifopt::Component
 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
 

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 >
 
- Public Types inherited from ifopt::ConstraintSet
typedef std::shared_ptr< ConstraintSetPtr
 
typedef Composite::Ptr VariablesPtr
 
- Public Types inherited from ifopt::Component
typedef Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
 
typedef std::shared_ptr< ComponentPtr
 
typedef std::vector< BoundsVecBound
 
typedef Eigen::VectorXd VectorXd
 
- Static Public Attributes inherited from ifopt::Component
static const int kSpecifyLater
 
- Protected Member Functions inherited from towr::TimeDiscretizationConstraint
int GetNumberOfNodes () const
 
- Protected Member Functions inherited from ifopt::ConstraintSet
const VariablesPtr GetVariables () const
 
- Protected Attributes inherited from towr::TimeDiscretizationConstraint
VecTimes dts_
 times at which the constraint is evaluated. More...
 

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 RangeOfMotionConstraint.

Definition at line 48 of file base_motion_constraint.h.

Constructor & Destructor Documentation

towr::BaseMotionConstraint::BaseMotionConstraint ( double  T,
double  dt,
const SplineHolder spline_holder 
)

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

Parameters
TThe total time of the optimization horizon.
dtThe discretization interval of the constraints.
spline_holderHolds pointers to the base variables.

Definition at line 38 of file base_motion_constraint.cc.

virtual towr::BaseMotionConstraint::~BaseMotionConstraint ( )
virtualdefault

Member Function Documentation

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

Definition at line 88 of file base_motion_constraint.cc.

void towr::BaseMotionConstraint::UpdateBoundsAtInstance ( double  t,
int  k,
VecBound b 
) const
overridevirtual

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

Implements towr::TimeDiscretizationConstraint.

Definition at line 69 of file base_motion_constraint.cc.

void towr::BaseMotionConstraint::UpdateConstraintAtInstance ( double  t,
int  k,
VectorXd g 
) const
overridevirtual

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

Implements towr::TimeDiscretizationConstraint.

Definition at line 61 of file base_motion_constraint.cc.

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
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.

Implements towr::TimeDiscretizationConstraint.

Definition at line 76 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.

VecBound towr::BaseMotionConstraint::node_bounds_
private

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
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 13 2019 02:28:00