Namespace for all structures of the RobotDynamics library. More...
Namespaces | |
Math | |
Math types such as vectors and matrices and utility functions. | |
Utils | |
Namespace that contains optional helper functions. | |
Classes | |
struct | Body |
Describes all properties of a single body. More... | |
struct | ConstraintSet |
Structure that contains both constraint information and workspace memory. More... | |
struct | CustomJoint |
CustomJoint is a struct used to create a joint with user defined parameters. This is accomplished by overriding the RobotDynamics::Joint::jcalc methods that calculate each joints kinematic parameters. More... | |
struct | FixedBody |
Keeps the information of a body and how it is attached to another body. More... | |
class | FixedReferenceFrame |
class | FrameObject |
An interface that objects with a ReferenceFrame extend to inherit the FrameObject::changeFrame method. More... | |
struct | Joint |
Describes a joint relative to the predecessor body. More... | |
struct | Model |
Contains all information about the rigid body model. More... | |
class | RdlException |
A custom exception. More... | |
class | ReferenceFrame |
ReferenceFrame object used to tell what frame objects are expressed in. Every ReferenceFrame has a pointer to its parent ReferenceFrame. This parent frame is NOT allowed to be nullptr. The ONLY ReferenceFrame that is allowed to have parentFrame=nullptr is the world frame. There is only one world frame and it can be accessed by the static method ReferenceFrame::getWorldFrame() which will return a shared_ptr to the world frame. This class and its implementation are an adaptation of ReferenceFrame.java by Jerry Pratt and the IHMC Robotics Group. More... | |
class | ReferenceFrameException |
A custom exception for frame operations. More... | |
Typedefs | |
typedef std::shared_ptr< FixedReferenceFrame > | FixedReferenceFramePtr |
typedef std::vector< FixedReferenceFramePtr > | FixedReferenceFramePtrV |
typedef std::shared_ptr< Model > | ModelPtr |
typedef std::shared_ptr< ReferenceFrame > | ReferenceFramePtr |
typedef std::vector< ReferenceFramePtr > | ReferenceFramePtrV |
Enumerations | |
enum | JointType { JointTypeUndefined = 0, JointTypeRevolute, JointTypePrismatic, JointTypeRevoluteX, JointTypeRevoluteY, JointTypeRevoluteZ, JointTypeSpherical, JointTypeEulerZYX, JointTypeEulerXYZ, JointTypeEulerYXZ, JointTypeTranslationXYZ, JointTypeFloatingBase, JointTypeFixed, JointType1DoF, JointType2DoF, JointType3DoF, JointType4DoF, JointType5DoF, JointType6DoF, JointTypeCustom } |
General types of joints. More... | |
Functions | |
void | calcBodyGravityWrench (Model &model, unsigned int body_id, RobotDynamics::Math::SpatialForce &gravity_wrench) |
Calculate the wrench due to gravity on a body. More... | |
void | calcBodySpatialJacobian (Model &model, const Math::VectorNd &Q, unsigned int body_id, Math::MatrixNd &G, bool update_kinematics=true) |
Computes the spatial jacobian for a body. The result will be returned via the G argument and represents the body Jacobian expressed at the origin of the body. The corresponding spatial velocity of the body w.r.t the world frame expressed in body frame can be calculated, for the body, as . For the spatial jacobian of body , each column j is computed as follows. More... | |
void | calcBodySpatialJacobianDot (Model &model, const Math::VectorNd &Q, const Math::VectorNd QDot, unsigned int body_id, Math::MatrixNd &G, const bool update_kinematics=true) |
Computes the time derivative of the spatial jacobian for a body. The result will be returned via the G argument and represents the time derivative of the body Jacobian expressed at the origin of the body. The corresponding spatial acceleration of the body w.r.t the world frame expressed in body frame can be calculated, for the th body, as where is the body jacobian of body . More... | |
void | calcContactJacobian (Model &model, const Math::VectorNd &Q, const ConstraintSet &CS, Math::MatrixNd &G, bool update_kinematics=true) |
Computes the Jacobian for the given ConstraintSet. More... | |
void | calcContactSystemVariables (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS) |
void | calcMInvTimesTau (Model &model, const Math::VectorNd &Q, const Math::VectorNd &Tau, Math::VectorNd &QDDot, bool update_kinematics=true) |
Computes the effect of multiplying the inverse of the joint space inertia matrix with a vector in linear time. More... | |
Math::FrameVector | calcPointAcceleration (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &QDDot, unsigned int body_id, const Math::Vector3d &point_position, bool update_kinematics=true) |
Computes the linear acceleration of a point on a body. More... | |
Math::FrameVectorPair | calcPointAcceleration6D (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &QDDot, unsigned int body_id, const Math::Vector3d &point_position, bool update_kinematics=true) |
Computes linear and angular acceleration of a point on a body. More... | |
Math::FrameVectorPair | calcPointAcceleration6D (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &QDDot, ReferenceFramePtr body_frame, ReferenceFramePtr relative_body_frame, ReferenceFramePtr expressedInFrame=nullptr, const bool update_kinematics=true) |
Computes linear and angular acceleration of a reference frame, relative to another reference frame and expressed in a third reference frame. More... | |
void | calcPointJacobian (Model &model, const Math::VectorNd &Q, unsigned int body_id, const Math::Vector3d &point_position, Math::MatrixNd &G, bool update_kinematics=true) |
Computes the 3D point jacobian for a point on a body. More... | |
void | calcPointJacobian (Model &model, const Math::VectorNd &Q, Math::MatrixNd &G, ReferenceFramePtr frame, bool update_kinematics=true) |
Compute the 3D point jacobian of the origin of a reference frame If a position of a point is computed by a function for which its time derivative is then this function computes the jacobian matrix . More... | |
void | calcPointJacobian6D (Model &model, const Math::VectorNd &Q, Math::MatrixNd &G, ReferenceFramePtr frame, bool update_kinematics=true) |
Compute the 6D point jacobian of the origin of a reference frame If a position of a point is computed by a function for which its time derivative is then this function computes the jacobian matrix . More... | |
void | calcPointJacobian6D (Model &model, const Math::VectorNd &Q, unsigned int body_id, const Math::Vector3d &point_position, Math::MatrixNd &G, bool update_kinematics=true) |
Computes a 6-D Jacobian for a point on a body. More... | |
void | calcPointJacobianDot (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, unsigned int body_id, const Math::Vector3d &point_position, Math::MatrixNd &G, bool update_kinematics=true) |
Computes the time derivative of the linear components the a point jacobian on a body. More... | |
void | calcPointJacobianDot (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, RobotDynamics::ReferenceFramePtr frame, Math::MatrixNd &G, bool update_kinematics=true) |
Computes the time derivative of a point jacobian of a point on a body. Only computes the linear elemets. More... | |
void | calcPointJacobianDot6D (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, RobotDynamics::ReferenceFramePtr frame, Math::MatrixNd &G, bool update_kinematics=true) |
Computes the time derivative of a point jacobian of a point on a body. More... | |
void | calcPointJacobianDot6D (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, unsigned int body_id, const Math::Vector3d &point_position, Math::MatrixNd &G, bool update_kinematics=true) |
Computes the 6D time derivative of a point jacobian on a body. More... | |
Math::FrameVector | calcPointVelocity (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, unsigned int body_id, const Math::Vector3d &point_position, bool update_kinematics=true) |
Computes the velocity of a point on a body. More... | |
Math::FrameVectorPair | calcPointVelocity6D (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, unsigned int body_id, const Math::Vector3d &point_position, bool update_kinematics=true) |
Computes angular and linear velocity of a point that is fixed on a body. More... | |
Math::FrameVectorPair | calcPointVelocity6D (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, RobotDynamics::ReferenceFramePtr frame, bool update_kinematics=true) |
Computes angular and linear velocity of the origin of a reference frame relative to world and expressed in world frame. More... | |
Math::FrameVectorPair | calcPointVelocity6D (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, RobotDynamics::ReferenceFramePtr baseFrame, RobotDynamics::ReferenceFramePtr relativeFrame, RobotDynamics::ReferenceFramePtr expressedInFrame=RobotDynamics::ReferenceFrame::getWorldFrame(), bool update_kinematics=true) |
Computes angular and linear velocity of the origin of a reference frame relative to another reference frame and expressed in a third reference frame. More... | |
void | calcRelativeBodySpatialJacobian (Model &model, const Math::VectorNd &Q, Math::MatrixNd &G, ReferenceFramePtr baseFrame, ReferenceFramePtr relativeFrame, ReferenceFramePtr expressedInFrame=nullptr, bool update_kinematics=true) |
Computes the jacobian of a frame with being the "base" frame, being the "relative" frame, and being the "expressed in" frame. Multiplying this jacobian by a vector of joint velocities will result in the spatial motion of the baseFrame w.r.t relativeFrame expressed in expressedInFrame, a.k.a . More... | |
void | calcRelativeBodySpatialJacobianAndJacobianDot (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::MatrixNd &G, Math::MatrixNd &GDot, ReferenceFramePtr baseFrame, ReferenceFramePtr relativeFrame, ReferenceFramePtr expressedInFrame=nullptr, bool update_kinematics=true) |
Computes both the body spatial jacobian and its time derivative. This function will be a bit more efficient at computing the jacobian and it's time derivative if you need both matrices rather than computing them with separate function calls. More... | |
void | calcRelativeBodySpatialJacobianDot (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::MatrixNd &G, ReferenceFramePtr baseFrame, ReferenceFramePtr relativeFrame, ReferenceFramePtr expressedInFrame=nullptr, bool update_kinematics=true) |
Computes the rate of change of the jacobian, , with being the "base" frame, being the relative" frame, and \f$k\f$ being the "expressed in" frame. This jacobian is such that the following is true, where is the spatial acceleration of frame w.r.t frame , expressed in frame . Additionally the jacobian can be computed by RobotDynamics::calcRelativeBodySpatialJacobian. More... | |
void | calcRelativePointJacobian6D (Model &model, const Math::VectorNd &Q, Math::MatrixNd &G, ReferenceFramePtr baseFrame, ReferenceFramePtr relativeFrame, ReferenceFramePtr expressedInFrame=RobotDynamics::ReferenceFrame::getWorldFrame(), bool update_kinematics=true) |
Compute the 6D jacobian of the origin of a reference frame relative to the origin of another reference frame and express the result in a third frame. More... | |
void | calcRelativePointJacobianAndJacobianDot6D (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::MatrixNd &G, Math::MatrixNd &GDot, ReferenceFramePtr baseFrame, ReferenceFramePtr relativeFrame, ReferenceFramePtr expressedInFrame=RobotDynamics::ReferenceFrame::getWorldFrame(), bool update_kinematics=true) |
Compute the point Jacobian of the origin of baseFrame, relative to the origin of relativeFrame, expressed in expressedInFrame. Also compute that point Jacobians time derivative. More... | |
void | calcRelativePointJacobianDot6D (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::MatrixNd &G, ReferenceFramePtr baseFrame, ReferenceFramePtr relativeFrame, ReferenceFramePtr expressedInFrame=RobotDynamics::ReferenceFrame::getWorldFrame(), bool update_kinematics=true) |
Compute the time derivative of the 6D jacobian of the origin of a reference frame relative to the origin of another reference frame and express the result in a third frame. More... | |
Math::SpatialAcceleration | calcSpatialAcceleration (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &QDDot, const unsigned int body_id, const unsigned int relative_body_id, ReferenceFramePtr expressedInFrame=nullptr, const bool update_kinematics=true) |
Compute the spatial acceleration of any body with respect to any other body and express the result in an arbitrary reference frame. The returned RobotDynamicS::Math::SpatialAcceleration can be expressed in the reference frame of choice by supplying the expressedInFrame argument. If left to the default value of nullptr, the result will be expressed in the reference frame corresponding to body_id. More... | |
Math::SpatialAcceleration | calcSpatialAcceleration (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &QDDot, ReferenceFramePtr body_frame, ReferenceFramePtr relative_body_frame, ReferenceFramePtr expressedInFrame=nullptr, const bool update_kinematics=true) |
Compute the spatial acceleration of any frame with respect to any other frame and express the result in an arbitrary third frame. The returned RobotDynamicS::Math::SpatialAcceleration can be expressed in the reference frame of choice by supplying the expressedInFrame argument. If left to the default value of nullptr, the result will be expressed in body_frame. More... | |
Math::SpatialMotion | calcSpatialVelocity (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, ReferenceFramePtr body_frame, ReferenceFramePtr relative_body_frame, ReferenceFramePtr expressedInFrame=nullptr, const bool update_kinematics=true) |
Compute the spatial velocity of any frame with respect to any other frame, expressed in an arbirtary third frame. The returned RobotDynamicS::Math::SpatialMotion is expressed in body_frame unless th expressedInFrame is provided. Each time RobotDynamics::updateKinematics is called, the spatial velocity of each body with respect to the world, and expressed in body frame is calculated. For body this is written as . Given another body, body , the velocity of body relative to body and expressed in body frame is computed by,
. More... | |
Math::SpatialMotion | calcSpatialVelocity (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const unsigned int body_id, const unsigned int relative_body_id, ReferenceFramePtr expressedInFrame=nullptr, const bool update_kinematics=true) |
Compute the spatial velocity of any body with respect to any other body. The returned RobotDynamicS::Math::SpatialMotion is expressed in the body frame of body body_id. Each time RobotDynamics::updateKinematics is called, the spatial velocity of each body with respect to the world, and expressed in body frame is calculated. For body this is written as . Given another body, body , the velocity of body relative to body and expressed in body frame is computed by,
. More... | |
void | compositeRigidBodyAlgorithm (Model &model, const Math::VectorNd &Q, Math::MatrixNd &H, bool update_kinematics=true) |
Computes the joint space inertia matrix by using the Composite Rigid Body Algorithm. More... | |
void | computeContactImpulsesDirect (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDotMinus, ConstraintSet &CS, Math::VectorNd &QDotPlus) |
Computes contact gain by constructing and solving the full lagrangian equation. More... | |
void | computeContactImpulsesNullSpace (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDotMinus, ConstraintSet &CS, Math::VectorNd &QDotPlus) |
Resolves contact gain using solveContactSystemNullSpace() More... | |
void | computeContactImpulsesRangeSpaceSparse (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDotMinus, ConstraintSet &CS, Math::VectorNd &QDotPlus) |
Resolves contact gain using solveContactSystemRangeSpaceSparse() More... | |
void | coriolisEffects (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::VectorNd &Tau, bool update_kinematics=true) |
Computes the coriolis forces. More... | |
void | forwardDynamics (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, Math::VectorNd &QDDot, Math::SpatialForceV *f_ext=nullptr, bool update_kinematics=true) |
Computes forward dynamics with the Articulated Body Algorithm. More... | |
void | forwardDynamicsAccelerationDeltas (Model &model, ConstraintSet &CS, VectorNd &QDDot_t, const unsigned int body_id, const SpatialForceV &f_t) |
Computes the effect of external forces on the generalized accelerations. More... | |
void | forwardDynamicsApplyConstraintForces (Model &model, const VectorNd &Tau, ConstraintSet &CS, VectorNd &QDDot) |
Compute only the effects of external forces on the generalized accelerations. More... | |
void | forwardDynamicsContactsDirect (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS, Math::VectorNd &QDDot) |
Computes forward dynamics with contact by constructing and solving the full lagrangian equation. More... | |
void | forwardDynamicsContactsKokkevis (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS, Math::VectorNd &QDDot) |
Computes forward dynamics that accounts for active contacts in ConstraintSet. More... | |
void | forwardDynamicsContactsNullSpace (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS, Math::VectorNd &QDDot) |
void | forwardDynamicsContactsRangeSpaceSparse (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS, Math::VectorNd &QDDot) |
void | forwardDynamicsLagrangian (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, Math::VectorNd &QDDot, Math::MatrixNd &H, Math::VectorNd &C, Math::LinearSolver linear_solver=Math::LinearSolverColPivHouseholderQR, Math::SpatialForceV *f_ext=nullptr, bool update_kinematics=true) |
Computes forward dynamics by building and solving the full Lagrangian equation. More... | |
void | gravityEffects (Model &model, Math::VectorNd &Tau) |
Computes the gravity vector. More... | |
void | inverseDynamics (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &QDDot, Math::VectorNd &Tau, Math::SpatialForceV *f_ext=nullptr, bool update_kinematics=true) |
bool | inverseKinematics (Model &model, const Math::VectorNd &Qinit, const std::vector< unsigned int > &body_id, const std::vector< Math::Vector3d > &body_point, const std::vector< Math::Vector3d > &target_pos, Math::VectorNd &Qres, double step_tol=1.0e-12, double lambda=0.01, unsigned int max_iter=50) |
Computes the inverse kinematics iteratively using a damped Levenberg-Marquardt method (also known as Damped Least Squares method) More... | |
bool | inverseKinematics (Model &model, const VectorNd &Qinit, const std::vector< unsigned int > &body_id, const std::vector< Vector3d > &body_point, const std::vector< Vector3d > &target_pos, VectorNd &Qres, double step_tol, double lambda, unsigned int max_iter) |
void | jcalc (Model &model, unsigned int joint_id, const Math::VectorNd &q, const Math::VectorNd &qdot) |
Computes all variables for a joint model and updates the body frame as well as the body's center of mass frame. More... | |
void | jcalc_X_lambda_S (Model &model, unsigned int joint_id, const Math::VectorNd &q) |
Math::SpatialTransform | jcalc_XJ (Model &model, unsigned int joint_id, const Math::VectorNd &q) |
void | nonlinearEffects (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::VectorNd &Tau, bool update_kinematics=true) |
Computes the coriolis forces. More... | |
void | set_zero (std::vector< SpatialVector > &spatial_values) |
void | solveContactSystemDirect (Math::MatrixNd &H, const Math::MatrixNd &G, const Math::VectorNd &c, const Math::VectorNd &gamma, Math::VectorNd &qddot, 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... | |
void | solveContactSystemNullSpace (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... | |
void | solveContactSystemRangeSpaceSparse (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... | |
void | updateAccelerations (Model &model, const Math::VectorNd &QDDot) |
Computes only the accelerations of the bodies. More... | |
void | updateKinematics (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &QDDot) |
Updates and computes velocities and accelerations of the bodies. More... | |
void | updateKinematicsCustom (Model &model, const Math::VectorNd *Q, const Math::VectorNd *QDot=nullptr, const Math::VectorNd *QDDot=nullptr) |
Selectively updates model internal states of body positions, velocities and/or accelerations. More... | |
void | updateKinematicsCustomParallel (Model &model, const Math::VectorNd *Q, const Math::VectorNd *QDot=nullptr, const Math::VectorNd *QDDot=nullptr) |
Selectively updates model internal states of body positions, velocities and/or accelerations and spawns threads far each branched chain. More... | |
void | updateKinematicsParallel (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &QDDot) |
Updates and computes velocities and accelerations of the bodies. More... | |
Namespace for all structures of the RobotDynamics library.
typedef std::shared_ptr<Model> RobotDynamics::ModelPtr |
General types of joints.
void RobotDynamics::forwardDynamicsAccelerationDeltas | ( | Model & | model, |
ConstraintSet & | CS, | ||
VectorNd & | QDDot_t, | ||
const unsigned int | body_id, | ||
const SpatialForceV & | f_t | ||
) |
Computes the effect of external forces on the generalized accelerations.
This function is essentially similar to ForwardDynamics() except that it tries to only perform computations of variables that change due to external forces defined in f_t.
Definition at line 568 of file Contacts.cc.
void RobotDynamics::forwardDynamicsApplyConstraintForces | ( | Model & | model, |
const VectorNd & | Tau, | ||
ConstraintSet & | CS, | ||
VectorNd & | QDDot | ||
) |
Compute only the effects of external forces on the generalized accelerations.
This function is a reduced version of ForwardDynamics() which only computes the effects of the external forces on the generalized accelerations.
Definition at line 445 of file Contacts.cc.
bool RobotDynamics::inverseKinematics | ( | Model & | model, |
const VectorNd & | Qinit, | ||
const std::vector< unsigned int > & | body_id, | ||
const std::vector< Vector3d > & | body_point, | ||
const std::vector< Vector3d > & | target_pos, | ||
VectorNd & | Qres, | ||
double | step_tol, | ||
double | lambda, | ||
unsigned int | max_iter | ||
) |
Definition at line 1878 of file Kinematics.cc.
void RobotDynamics::jcalc | ( | Model & | model, |
unsigned int | joint_id, | ||
const Math::VectorNd & | q, | ||
const Math::VectorNd & | qdot | ||
) |
Computes all variables for a joint model and updates the body frame as well as the body's center of mass frame.
By appropriate modification of this function all types of joints can be modeled. See RobotDynamics::CustomJoint
model | the rigid body model |
joint_id | the id of the joint we are interested in. This will be used to determine the type of joint and also the entries of . |
q | joint state variables |
qdot | joint velocity variables |
void RobotDynamics::jcalc_X_lambda_S | ( | Model & | model, |
unsigned int | joint_id, | ||
const Math::VectorNd & | q | ||
) |
Math::SpatialTransform RobotDynamics::jcalc_XJ | ( | Model & | model, |
unsigned int | joint_id, | ||
const Math::VectorNd & | q | ||
) |
|
inline |
Definition at line 674 of file Contacts.cc.