Structure that contains both constraint information and workspace memory. More...
#include <Contacts.h>
Public Member Functions | |
unsigned int | addConstraint (unsigned int body_id, const Math::Vector3d &body_point, const Math::Vector3d &world_normal, const char *constraint_name=NULL, double normal_acceleration=0.) |
Adds a constraint to the constraint set. More... | |
bool | bind (const Model &model) |
Initializes and allocates memory for the constraint set. More... | |
void | clear () |
Clears all variables in the constraint set. More... | |
ConstraintSet () | |
ConstraintSet | Copy () |
Copies the constraints and resets its ConstraintSet::bound flag. More... | |
void | setSolver (Math::LinearSolver solver) |
Specifies which method should be used for solving undelying linear systems. More... | |
size_t | size () const |
Returns the number of constraints. More... | |
Public Attributes | |
Math::MatrixNd | A |
Workspace for the Lagrangian left-hand-side matrix. More... | |
Math::VectorNd | a |
Workspace for the accelerations of due to the test forces. More... | |
Math::VectorNd | acceleration |
Math::VectorNd | b |
Workspace for the Lagrangian right-hand-side. More... | |
std::vector< unsigned int > | body |
bool | bound |
Whether the constraint set was bound to a model (mandatory!). More... | |
Math::VectorNd | C |
Workspace for the coriolis forces. More... | |
std::vector< Math::SpatialVector > | d_a |
Workspace for the acceleration due to the test force. More... | |
Math::VectorNd | d_d |
Workspace when applying constraint forces. More... | |
std::vector< Math::SpatialMatrix > | d_IA |
Workspace for the inertia when applying constraint forces. More... | |
std::vector< Math::Vector3d > | d_multdof3_u |
Math::SpatialForceV | d_pA |
Workspace for the bias force due to the test force. More... | |
Math::VectorNd | d_u |
std::vector< Math::SpatialVector > | d_U |
Workspace when applying constraint forces. More... | |
Math::SpatialForceV | f_ext_constraints |
Workspace for the actual spatial forces. More... | |
Math::SpatialForceV | f_t |
Workspace for the test forces. More... | |
Math::VectorNd | force |
Math::MatrixNd | G |
Math::VectorNd | gamma |
Workspace of the lower part of b. More... | |
Eigen::HouseholderQR< Math::MatrixNd > | GT_qr |
Workspace for the QR decomposition of the null-space method. More... | |
Math::MatrixNd | GT_qr_Q |
Math::MatrixNd | H |
Workspace for the joint space inertia matrix. More... | |
Math::VectorNd | impulse |
Math::MatrixNd | K |
Workspace for the Inverse Articulated-Body Inertia. More... | |
Math::LinearSolver | linear_solver |
Method that should be used to solve internal linear systems. More... | |
std::vector< std::string > | name |
std::vector< Math::Vector3d > | normal |
std::vector< Math::Vector3d > | point |
std::vector< Math::Vector3d > | point_accel_0 |
Workspace for the default point accelerations. More... | |
Math::VectorNd | QDDot_0 |
Workspace for the default accelerations. More... | |
Math::VectorNd | QDDot_t |
Workspace for the test accelerations. More... | |
Math::VectorNd | qddot_y |
Math::VectorNd | qddot_z |
Math::VectorNd | v_plus |
Math::VectorNd | x |
Workspace for the Lagrangian solution. More... | |
Math::MatrixNd | Y |
Math::MatrixNd | Z |
Structure that contains both constraint information and workspace memory.
This structure is used to reduce the amount of memory allocations that are needed when computing constraint forces.
The ConstraintSet has to be bound to a model using ConstraintSet::bind() before it can be used in ForwardDynamicsContacts .
Definition at line 168 of file Contacts.h.
|
inline |
Definition at line 170 of file Contacts.h.
unsigned int RobotDynamics::ConstraintSet::addConstraint | ( | unsigned int | body_id, |
const Math::Vector3d & | body_point, | ||
const Math::Vector3d & | world_normal, | ||
const char * | constraint_name = NULL , |
||
double | normal_acceleration = 0. |
||
) |
Adds a constraint to the constraint set.
body_id | the body which is affected directly by the constraint |
body_point | the point that is constrained relative to the contact body |
world_normal | the normal along the constraint acts (in base coordinates) |
constraint_name | a human readable name (optional, default: NULL) |
normal_acceleration | the acceleration of the contact along the normal (optional, default: 0.) |
Definition at line 27 of file Contacts.cc.
bool RobotDynamics::ConstraintSet::bind | ( | const Model & | model | ) |
Initializes and allocates memory for the constraint set.
This function allocates memory for temporary values and matrices that are required for contact force computation. Both model and constraint set must not be changed after a binding as the required memory is dependent on the model size (i.e. the number of bodies and degrees of freedom) and the number of constraints in the Constraint set.
The values of ConstraintSet::acceleration may still be modified after the set is bound to the model.
Definition at line 62 of file Contacts.cc.
void RobotDynamics::ConstraintSet::clear | ( | ) |
Clears all variables in the constraint set.
Definition at line 127 of file Contacts.cc.
|
inline |
Copies the constraints and resets its ConstraintSet::bound flag.
Definition at line 191 of file Contacts.h.
|
inline |
Specifies which method should be used for solving undelying linear systems.
Definition at line 202 of file Contacts.h.
|
inline |
Returns the number of constraints.
Definition at line 221 of file Contacts.h.
Math::MatrixNd RobotDynamics::ConstraintSet::A |
Workspace for the Lagrangian left-hand-side matrix.
Definition at line 267 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::a |
Workspace for the accelerations of due to the test forces.
Definition at line 290 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::acceleration |
Enforced accelerations of the contact points along the contact normal.
Definition at line 242 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::b |
Workspace for the Lagrangian right-hand-side.
Definition at line 270 of file Contacts.h.
std::vector<unsigned int> RobotDynamics::ConstraintSet::body |
Definition at line 236 of file Contacts.h.
bool RobotDynamics::ConstraintSet::bound |
Whether the constraint set was bound to a model (mandatory!).
Definition at line 233 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::C |
Workspace for the coriolis forces.
Definition at line 260 of file Contacts.h.
std::vector<Math::SpatialVector> RobotDynamics::ConstraintSet::d_a |
Workspace for the acceleration due to the test force.
Definition at line 311 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::d_d |
Workspace when applying constraint forces.
Definition at line 321 of file Contacts.h.
std::vector<Math::SpatialMatrix> RobotDynamics::ConstraintSet::d_IA |
Workspace for the inertia when applying constraint forces.
Definition at line 315 of file Contacts.h.
std::vector<Math::Vector3d> RobotDynamics::ConstraintSet::d_multdof3_u |
Definition at line 323 of file Contacts.h.
Math::SpatialForceV RobotDynamics::ConstraintSet::d_pA |
Workspace for the bias force due to the test force.
Definition at line 308 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::d_u |
Definition at line 312 of file Contacts.h.
std::vector<Math::SpatialVector> RobotDynamics::ConstraintSet::d_U |
Workspace when applying constraint forces.
Definition at line 318 of file Contacts.h.
Math::SpatialForceV RobotDynamics::ConstraintSet::f_ext_constraints |
Workspace for the actual spatial forces.
Definition at line 302 of file Contacts.h.
Math::SpatialForceV RobotDynamics::ConstraintSet::f_t |
Workspace for the test forces.
Definition at line 299 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::force |
Actual constraint forces along the contact normals.
Definition at line 245 of file Contacts.h.
Math::MatrixNd RobotDynamics::ConstraintSet::G |
Definition at line 264 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::gamma |
Workspace of the lower part of b.
Definition at line 263 of file Contacts.h.
Eigen::HouseholderQR<Math::MatrixNd> RobotDynamics::ConstraintSet::GT_qr |
Workspace for the QR decomposition of the null-space method.
Definition at line 276 of file Contacts.h.
Math::MatrixNd RobotDynamics::ConstraintSet::GT_qr_Q |
Definition at line 278 of file Contacts.h.
Math::MatrixNd RobotDynamics::ConstraintSet::H |
Workspace for the joint space inertia matrix.
Definition at line 257 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::impulse |
Actual constraint impulses along the contact normals.
Definition at line 248 of file Contacts.h.
Math::MatrixNd RobotDynamics::ConstraintSet::K |
Workspace for the Inverse Articulated-Body Inertia.
Definition at line 287 of file Contacts.h.
Math::LinearSolver RobotDynamics::ConstraintSet::linear_solver |
Method that should be used to solve internal linear systems.
Definition at line 230 of file Contacts.h.
std::vector<std::string> RobotDynamics::ConstraintSet::name |
Definition at line 235 of file Contacts.h.
std::vector<Math::Vector3d> RobotDynamics::ConstraintSet::normal |
Definition at line 238 of file Contacts.h.
std::vector<Math::Vector3d> RobotDynamics::ConstraintSet::point |
Definition at line 237 of file Contacts.h.
std::vector<Math::Vector3d> RobotDynamics::ConstraintSet::point_accel_0 |
Workspace for the default point accelerations.
Definition at line 305 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::QDDot_0 |
Workspace for the default accelerations.
Definition at line 296 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::QDDot_t |
Workspace for the test accelerations.
Definition at line 293 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::qddot_y |
Definition at line 281 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::qddot_z |
Definition at line 282 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::v_plus |
The velocities we want to have along the contact normals after calling ComputeContactImpulsesLagrangian
Definition at line 252 of file Contacts.h.
Math::VectorNd RobotDynamics::ConstraintSet::x |
Workspace for the Lagrangian solution.
Definition at line 273 of file Contacts.h.
Math::MatrixNd RobotDynamics::ConstraintSet::Y |
Definition at line 279 of file Contacts.h.
Math::MatrixNd RobotDynamics::ConstraintSet::Z |
Definition at line 280 of file Contacts.h.