|
RBDL_DLLAPI void | CalcConstraintsPositionError (Model &model, const Math::VectorNd &Q, ConstraintSet &CS, Math::VectorNd &errOutput, bool update_kinematics=true) |
| Computes the position errors for the given ConstraintSet. More...
|
|
RBDL_DLLAPI void | CalcConstraintsJacobian (Model &model, const Math::VectorNd &Q, ConstraintSet &CS, Math::MatrixNd &GOutput, bool update_kinematics=true) |
| Computes the Jacobian for the given ConstraintSet. More...
|
|
RBDL_DLLAPI void | CalcConstraintsVelocityError (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, ConstraintSet &CS, Math::VectorNd &errOutput, bool update_kinematics=true) |
| Computes the velocity errors for the given ConstraintSet. More...
|
|
RBDL_DLLAPI void | CalcConstrainedSystemVariables (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CSOutput, bool update_kinematics=true, std::vector< Math::SpatialVector > *f_ext=NULL) |
| Computes the terms , , and of the constrained dynamic problem and stores them in the ConstraintSet. More...
|
|
RBDL_DLLAPI bool | CalcAssemblyQ (Model &model, Math::VectorNd QInit, ConstraintSet &CS, Math::VectorNd &QOutput, const Math::VectorNd &weights, double tolerance=1e-12, unsigned int max_iter=100) |
| Computes a feasible initial value of the generalized joint positions. More...
|
|
RBDL_DLLAPI void | CalcAssemblyQDot (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDotInit, ConstraintSet &CS, Math::VectorNd &QDotOutput, const Math::VectorNd &weights) |
| Computes a feasible initial value of the generalized joint velocities. More...
|
|
RBDL_DLLAPI void | ForwardDynamicsConstraintsDirect (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS, Math::VectorNd &QDDotOutput, bool update_kinematics=true, std::vector< Math::SpatialVector > *f_ext=NULL) |
| Computes forward dynamics with contact by constructing and solving the full lagrangian equation. More...
|
|
RBDL_DLLAPI void | ForwardDynamicsConstraintsRangeSpaceSparse (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS, Math::VectorNd &QDDotOutput, bool update_kinematics=true, std::vector< Math::SpatialVector > *f_ext=NULL) |
|
RBDL_DLLAPI void | ForwardDynamicsConstraintsNullSpace (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS, Math::VectorNd &QDDotOutput, bool update_kinematics=true, std::vector< Math::SpatialVector > *f_ext=NULL) |
|
RBDL_DLLAPI void | ForwardDynamicsContactsKokkevis (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS, Math::VectorNd &QDDotOutput) |
| Computes forward dynamics that accounts for active contacts in ConstraintSet. More...
|
|
RBDL_DLLAPI void | InverseDynamicsConstraintsRelaxed (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &QDDotControls, ConstraintSet &CS, Math::VectorNd &QDDotOutput, Math::VectorNd &TauOutput, bool update_kinematics=true, std::vector< Math::SpatialVector > *f_ext=NULL) |
| A relaxed inverse-dynamics operator that can be applied to under-actuated or fully-actuated constrained multibody systems. More...
|
|
RBDL_DLLAPI void | InverseDynamicsConstraints (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &QDDotDesired, ConstraintSet &CS, Math::VectorNd &QDDotOutput, Math::VectorNd &TauOutput, bool update_kinematics=true, std::vector< Math::SpatialVector > *f_ext=NULL) |
| An inverse-dynamics operator that can be applied to fully-actuated constrained systems. More...
|
|
RBDL_DLLAPI bool | isConstrainedSystemFullyActuated (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, ConstraintSet &CS, bool update_kinematics=true, std::vector< Math::SpatialVector > *f_ext=NULL) |
| A method to evaluate if the constrained system is fully actuated. More...
|
|
RBDL_DLLAPI void | ComputeConstraintImpulsesDirect (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDotMinus, ConstraintSet &CS, Math::VectorNd &QDotPlusOutput) |
| Computes contact gain by constructing and solving the full lagrangian equation. More...
|
|
RBDL_DLLAPI void | ComputeConstraintImpulsesRangeSpaceSparse (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDotMinus, ConstraintSet &CS, Math::VectorNd &QDotPlusOutput) |
| Resolves contact gain using SolveContactSystemRangeSpaceSparse() More...
|
|
RBDL_DLLAPI void | ComputeConstraintImpulsesNullSpace (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDotMinus, ConstraintSet &CS, Math::VectorNd &QDotPlusOutput) |
| Resolves contact gain using SolveContactSystemNullSpace() More...
|
|
RBDL_DLLAPI void | SolveConstrainedSystemDirect (Math::MatrixNd &H, const Math::MatrixNd &G, const Math::VectorNd &c, const Math::VectorNd &gamma, Math::VectorNd &lambda, Math::MatrixNd &A, Math::VectorNd &b, Math::VectorNd &x, Math::LinearSolver &linear_solver) |
| Solves the full contact system directly, i.e. simultaneously for contact forces and joint accelerations. More...
|
|
RBDL_DLLAPI void | SolveConstrainedSystemRangeSpaceSparse (Model &model, Math::MatrixNd &H, const Math::MatrixNd &G, const Math::VectorNd &c, const Math::VectorNd &gamma, Math::VectorNd &qddot, Math::VectorNd &lambda, Math::MatrixNd &K, Math::VectorNd &a, Math::LinearSolver linear_solver) |
| Solves the contact system by first solving for the the joint accelerations and then the contact forces using a sparse matrix decomposition of the joint space inertia matrix. More...
|
|
RBDL_DLLAPI void | SolveConstrainedSystemNullSpace (Math::MatrixNd &H, const Math::MatrixNd &G, const Math::VectorNd &c, const Math::VectorNd &gamma, Math::VectorNd &qddot, Math::VectorNd &lambda, Math::MatrixNd &Y, Math::MatrixNd &Z, Math::VectorNd &qddot_y, Math::VectorNd &qddot_z, Math::LinearSolver &linear_solver) |
| Solves the contact system by first solving for the joint accelerations and then for the constraint forces. More...
|
|