Drake
QuasiStaticConstraint Class Reference

the Center of Mass (CoM) is within the support polygon. More...

#include <drake/systems/plants/constraint/RigidBodyConstraint.h>

Inheritance diagram for QuasiStaticConstraint:
Collaboration diagram for QuasiStaticConstraint:

Public Member Functions

 QuasiStaticConstraint (RigidBodyTree *robot, const Eigen::Vector2d &tspan=DrakeRigidBodyConstraint::default_tspan, const std::set< int > &robotnumset=QuasiStaticConstraint::defaultRobotNumSet)
 
virtual ~QuasiStaticConstraint (void)
 
bool isTimeValid (const double *t) const
 
int getNumConstraint (const double *t) const
 
void eval (const double *t, KinematicsCache< double > &cache, const double *weights, Eigen::VectorXd &c, Eigen::MatrixXd &dc) const
 
void bounds (const double *t, Eigen::VectorXd &lb, Eigen::VectorXd &ub) const
 
void name (const double *t, std::vector< std::string > &name_str) const
 
bool isActive () const
 
int getNumWeights () const
 
void addContact (int num_new_bodies, const int *body, const Eigen::Matrix3Xd *body_pts)
 
void setShrinkFactor (double factor)
 
void setActive (bool flag)
 
void updateRobot (RigidBodyTree *robot)
 
void updateRobotnum (std::set< int > &robotnumset)
 
- Public Member Functions inherited from RigidBodyConstraint
 RigidBodyConstraint (int category, RigidBodyTree *robot, const Eigen::Vector2d &tspan=DrakeRigidBodyConstraint::default_tspan)
 
int getType () const
 
int getCategory () const
 
RigidBodyTreegetRobotPointer () const
 
virtual ~RigidBodyConstraint (void)=0
 

Additional Inherited Members

- Static Public Attributes inherited from RigidBodyConstraint
static const int SingleTimeKinematicConstraintCategory = -1
 
static const int MultipleTimeKinematicConstraintCategory = -2
 
static const int QuasiStaticConstraintCategory = -3
 
static const int PostureConstraintCategory = -4
 
static const int MultipleTimeLinearPostureConstraintCategory = -5
 
static const int SingleTimeLinearPostureConstraintCategory = -6
 
static const int QuasiStaticConstraintType = 1
 
static const int PostureConstraintType = 2
 
static const int SingleTimeLinearPostureConstraintType = 3
 
static const int AllBodiesClosestDistanceConstraintType = 4
 
static const int WorldEulerConstraintType = 5
 
static const int WorldGazeDirConstraintType = 6
 
static const int WorldGazeOrientConstraintType = 7
 
static const int WorldGazeTargetConstraintType = 8
 
static const int RelativeGazeTargetConstraintType = 9
 
static const int WorldCoMConstraintType = 10
 
static const int WorldPositionConstraintType = 11
 
static const int WorldPositionInFrameConstraintType = 12
 
static const int WorldQuatConstraintType = 13
 
static const int Point2PointDistanceConstraintType = 14
 
static const int Point2LineSegDistConstraintType = 15
 
static const int WorldFixedPositionConstraintType = 16
 
static const int WorldFixedOrientConstraintType = 17
 
static const int WorldFixedBodyPoseConstraintType = 18
 
static const int PostureChangeConstraintType = 19
 
static const int RelativePositionConstraintType = 20
 
static const int RelativeQuatConstraintType = 24
 
static const int RelativeGazeDirConstraintType = 25
 
static const int MinDistanceConstraintType = 26
 
static const int GravityCompensationTorqueConstraintType = 27
 
- Protected Member Functions inherited from RigidBodyConstraint
std::string getTimeString (const double *t) const
 
void set_type (int type)
 
void set_robot (RigidBodyTree *robot)
 
const doubletspan () const
 

Detailed Description

the Center of Mass (CoM) is within the support polygon.

The support polygon is a shrunk area of the contact polygon

Parameters
robot
tspan– The time span of this constraint being active
robotnumset– The set of the robots in the RigidBodyTree for which the CoM is computed
shrinkFactor– The factor to shrink the contact polygon. The shrunk area is the support polygon.
active– Whether the constraint is on/off. If active = false, even the time t is within tspan, the constraint is still inactive
num_bodies– The total number of ground contact bodies/frames
num_pts– The total number of ground contact points
bodies– The index of ground contact bodies/frames
num_body_pts– The number of contact points on each contact body/frame
body_pts– The contact points on each contact body/frame

Function: eval –evaluate the constraint

Parameters
t–the time to evaluate the constraint
weights–the weight associate with each ground contact point
c– c = CoM-weights'*support_vertex
dc– dc = [dcdq dcdweiths] addContact – add contact body and points
num_new_bodies– number of new contact bodies
body– the index of new contact bodies/frames
body_pts– body_pts[i] are the contact points on body[i]

Constructor & Destructor Documentation

QuasiStaticConstraint ( RigidBodyTree robot,
const Eigen::Vector2d &  tspan = DrakeRigidBodyConstraint::default_tspan,
const std::set< int > &  robotnumset = QuasiStaticConstraint::defaultRobotNumSet 
)

Here is the call graph for this function:

~QuasiStaticConstraint ( void  )
virtual

Member Function Documentation

void addContact ( int  num_new_bodies,
const int *  body,
const Eigen::Matrix3Xd *  body_pts 
)

Here is the call graph for this function:

Here is the caller graph for this function:

void bounds ( const double t,
Eigen::VectorXd &  lb,
Eigen::VectorXd &  ub 
) const

Here is the call graph for this function:

Here is the caller graph for this function:

void eval ( const double t,
KinematicsCache< double > &  cache,
const double weights,
Eigen::VectorXd &  c,
Eigen::MatrixXd &  dc 
) const

Here is the call graph for this function:

Here is the caller graph for this function:

int getNumConstraint ( const double t) const

Here is the call graph for this function:

Here is the caller graph for this function:

int getNumWeights ( ) const
inline

Here is the caller graph for this function:

bool isActive ( ) const
inline

Here is the caller graph for this function:

bool isTimeValid ( const double t) const

Here is the call graph for this function:

Here is the caller graph for this function:

void name ( const double t,
std::vector< std::string > &  name_str 
) const

Here is the call graph for this function:

Here is the caller graph for this function:

void setActive ( bool  flag)
inline

Here is the caller graph for this function:

void setShrinkFactor ( double  factor)

Here is the caller graph for this function:

void updateRobot ( RigidBodyTree robot)

Here is the call graph for this function:

Here is the caller graph for this function:

void updateRobotnum ( std::set< int > &  robotnumset)

Here is the caller graph for this function:


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