Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
towr::RangeOfMotionConstraint Class Reference

Constrains an endeffector to lie in a box around the nominal stance. More...

#include <range_of_motion_constraint.h>

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

Public Types

using EE = uint
 
using Vector3d = Eigen::Vector3d
 
- Public Types inherited from towr::TimeDiscretizationConstraint
using Bounds = ifopt::Bounds
 
using VecTimes = std::vector< double >
 

Public Member Functions

 RangeOfMotionConstraint (const KinematicModel::Ptr &robot_model, const Parameters &params, const EE &ee, const SplineHolder &spline_holder)
 Constructs a constraint instance. More...
 
virtual ~RangeOfMotionConstraint ()=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 dimension) const
 
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...
 

Private Attributes

EulerConverter base_angular_
 the orientation of the base. More...
 
NodeSpline::Ptr base_linear_
 the linear position of the base. More...
 
EE ee_
 
NodeSpline::Ptr ee_motion_
 the linear position of the endeffectors. More...
 
Eigen::Vector3d max_deviation_from_nominal_
 
Eigen::Vector3d nominal_ee_pos_B_
 

Additional Inherited Members

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

Detailed Description

Constrains an endeffector to lie in a box around the nominal stance.

These constraints are necessary to avoid configurations that are outside the kinematic reach of the robot. The constraint is defined by Cartesian estimates of the reachability of each endeffector.

This constraint calculates the position of of the contact expressed in the current CoM frame and constrains it to lie in a box around the nominal/ natural contact position for that leg.

Definition at line 54 of file range_of_motion_constraint.h.

Member Typedef Documentation

Definition at line 56 of file range_of_motion_constraint.h.

using towr::RangeOfMotionConstraint::Vector3d = Eigen::Vector3d

Definition at line 57 of file range_of_motion_constraint.h.

Constructor & Destructor Documentation

towr::RangeOfMotionConstraint::RangeOfMotionConstraint ( const KinematicModel::Ptr robot_model,
const Parameters params,
const EE ee,
const SplineHolder spline_holder 
)

Constructs a constraint instance.

Parameters
robot_modelThe kinematic restrictions of the robot.
paramsParameters defining the optimization problem.
eeThe endeffector for which to constrain the range.
spline_holderPointer to the current variables.

Definition at line 35 of file range_of_motion_constraint.cc.

virtual towr::RangeOfMotionConstraint::~RangeOfMotionConstraint ( )
virtualdefault

Member Function Documentation

int towr::RangeOfMotionConstraint::GetRow ( int  node,
int  dimension 
) const
private

Definition at line 55 of file range_of_motion_constraint.cc.

void towr::RangeOfMotionConstraint::UpdateBoundsAtInstance ( double  t,
int  k,
VecBound &  b 
) const
overrideprivatevirtual

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 74 of file range_of_motion_constraint.cc.

void towr::RangeOfMotionConstraint::UpdateConstraintAtInstance ( double  t,
int  k,
VectorXd g 
) const
overrideprivatevirtual

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

void towr::RangeOfMotionConstraint::UpdateJacobianAtInstance ( double  t,
int  k,
std::string  var_set,
Jacobian &  jac 
) const
overrideprivatevirtual

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 86 of file range_of_motion_constraint.cc.

Member Data Documentation

EulerConverter towr::RangeOfMotionConstraint::base_angular_
private

the orientation of the base.

Definition at line 74 of file range_of_motion_constraint.h.

NodeSpline::Ptr towr::RangeOfMotionConstraint::base_linear_
private

the linear position of the base.

Definition at line 73 of file range_of_motion_constraint.h.

EE towr::RangeOfMotionConstraint::ee_
private

Definition at line 79 of file range_of_motion_constraint.h.

NodeSpline::Ptr towr::RangeOfMotionConstraint::ee_motion_
private

the linear position of the endeffectors.

Definition at line 75 of file range_of_motion_constraint.h.

Eigen::Vector3d towr::RangeOfMotionConstraint::max_deviation_from_nominal_
private

Definition at line 77 of file range_of_motion_constraint.h.

Eigen::Vector3d towr::RangeOfMotionConstraint::nominal_ee_pos_B_
private

Definition at line 78 of file range_of_motion_constraint.h.


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


towr_core
Author(s): Alexander W. Winkler
autogenerated on Sun Apr 8 2018 02:18:53