Algorithms
Centroidal
- ccrba((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v) numpy.ndarray :
Computes the centroidal mapping, the centroidal momentum and the Centroidal Composite Rigid Body Inertia, puts the result in Data and returns the centroidal mapping.For the same price, it also computes the total joint jacobians (
data.J
).
- computeCentroidalDynamicsDerivatives((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)a) tuple :
Computes the analytical derivatives of the centroidal dynamics with respect to the joint configuration vector, velocity and acceleration.
- computeCentroidalMap((Model)model, (Data)data, (numpy.ndarray)q) numpy.ndarray :
Computes the centroidal mapping, puts the result in Data.Ag and returns the centroidal mapping. For the same price, it also computes the total joint jacobians (
data.J
).
- computeCentroidalMapTimeVariation((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v) numpy.ndarray :
Computes the time derivative of the centroidal momentum matrix \(A_g\), puts the result in Data.Ag and returns the centroidal mapping. For the same price, it also computes the centroidal momentum matrix (
data.Ag
), the total joint jacobians (data.J
) and the related joint jacobians time derivative (data.dJ
)
- computeCentroidalMomentum((Model)model, (Data)data) Force :
Computes the Centroidal momentum, a.k.a. the total momentum of the system expressed around the center of mass.
- computeCentroidalMomentum((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v) Force :
Computes the Centroidal momentum, a.k.a. the total momentum of the system expressed around the center of mass.
- computeCentroidalMomentumTimeVariation((Model)model, (Data)data) Force :
Computes the Centroidal momentum and its time derivatives, a.k.a. the total momentum of the system and its time derivative expressed around the center of mass.
- computeCentroidalMomentumTimeVariation((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)a) Force :
Computes the Centroidal momentum and its time derivatives, a.k.a. the total momentum of the system and its time derivative expressed around the center of mass.
- dccrba((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v) numpy.ndarray :
Computes the time derivative of the centroidal momentum matrix \(A_g\) in terms of q and v. For the same price, it also computes the centroidal momentum matrix (
data.Ag
), the total joint jacobians (data.J
) and the related joint jacobians time derivative (data.dJ
)
- getCentroidalDynamicsDerivatives((Model)model, (Data)data) tuple :
Retrive the analytical derivatives of the centroidal dynamics from the RNEA derivatives.
pinocchio.computeRNEADerivatives
should have been called first.
Cholesky
- computeMinv((Model)Model, (Data)Data) numpy.ndarray :
Returns the inverse of the inverse of the joint space inertia matrix using the results of the Cholesky decomposition performed by
cholesky.decompose
. The result is stored indata.Minv
.
- decompose((Model)Model, (Data)Data) numpy.ndarray :
Computes the Cholesky decomposition of the joint space inertia matrix M contained in
data
. The upper triangular part ofdata.M
should have been filled first by callingcrba
, or any related algorithms.
- solve((Model)Model, (Data)Data, (numpy.ndarray)v) numpy.ndarray :
Returns the solution :math`x` of :math`Mx = y` using the Cholesky decomposition stored in
data
given the entry:math:y.
Collision Algorithms
- class BroadPhaseManager_DynamicAABBTreeArrayCollisionManager
Broad phase manager associated to hpp::fcl::DynamicAABBTreeArrayCollisionManager
- check((BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)self) bool :
Check whether the base broad phase manager is aligned with the current collision_objects.
- check((BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)self, (CollisionCallBackBase)callback) bool :
Check whether the callback is inline with *this.
- collide((BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)self, (CollisionObject)collision_object, (CollisionCallBackBase)callback) bool :
Performs collision test between one object and all the objects belonging to the manager.
- collide((BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)self, (CollisionCallBackBase)callback) bool :
Performs collision test for the objects belonging to the manager.
- collide((BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)self, (BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)other_manager, (CollisionCallBackBase)callback) bool :
Performs collision test with objects belonging to another manager.
- getCollisionObjectInflation((BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)self) object :
Returns the inflation value related to each collision object.
- getCollisionObjectStatus((BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)self) StdVec_Bool :
Returns the status of the collision object.
- getCollisionObjects((BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)self) StdVec_CollisionObject
- getGeometryData((BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)self) GeometryData :
Returns the related geometry data.
- getGeometryModel((BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)self) GeometryModel :
Returns the related geometry model.
- getManager((BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)self) DynamicAABBTreeArrayCollisionManager :
Returns the internal FCL manager
- getModel((BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)self) Model :
Returns the related model.
- update((BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)self[, (bool)compute_local_aabb=False]) None :
Update the manager from the current geometry positions and update the underlying FCL broad phase manager.
- update((BroadPhaseManager_DynamicAABBTreeArrayCollisionManager)self, (GeometryData)geom_data_new) None :
Update the manager with a new geometry data.
- class BroadPhaseManager_DynamicAABBTreeCollisionManager
Broad phase manager associated to hpp::fcl::DynamicAABBTreeCollisionManager
- check((BroadPhaseManager_DynamicAABBTreeCollisionManager)self) bool :
Check whether the base broad phase manager is aligned with the current collision_objects.
- check((BroadPhaseManager_DynamicAABBTreeCollisionManager)self, (CollisionCallBackBase)callback) bool :
Check whether the callback is inline with *this.
- collide((BroadPhaseManager_DynamicAABBTreeCollisionManager)self, (CollisionObject)collision_object, (CollisionCallBackBase)callback) bool :
Performs collision test between one object and all the objects belonging to the manager.
- collide((BroadPhaseManager_DynamicAABBTreeCollisionManager)self, (CollisionCallBackBase)callback) bool :
Performs collision test for the objects belonging to the manager.
- collide((BroadPhaseManager_DynamicAABBTreeCollisionManager)self, (BroadPhaseManager_DynamicAABBTreeCollisionManager)other_manager, (CollisionCallBackBase)callback) bool :
Performs collision test with objects belonging to another manager.
- getCollisionObjectInflation((BroadPhaseManager_DynamicAABBTreeCollisionManager)self) object :
Returns the inflation value related to each collision object.
- getCollisionObjectStatus((BroadPhaseManager_DynamicAABBTreeCollisionManager)self) StdVec_Bool :
Returns the status of the collision object.
- getCollisionObjects((BroadPhaseManager_DynamicAABBTreeCollisionManager)self) StdVec_CollisionObject
- getGeometryData((BroadPhaseManager_DynamicAABBTreeCollisionManager)self) GeometryData :
Returns the related geometry data.
- getGeometryModel((BroadPhaseManager_DynamicAABBTreeCollisionManager)self) GeometryModel :
Returns the related geometry model.
- getManager((BroadPhaseManager_DynamicAABBTreeCollisionManager)self) DynamicAABBTreeCollisionManager :
Returns the internal FCL manager
- getModel((BroadPhaseManager_DynamicAABBTreeCollisionManager)self) Model :
Returns the related model.
- update((BroadPhaseManager_DynamicAABBTreeCollisionManager)self[, (bool)compute_local_aabb=False]) None :
Update the manager from the current geometry positions and update the underlying FCL broad phase manager.
- update((BroadPhaseManager_DynamicAABBTreeCollisionManager)self, (GeometryData)geom_data_new) None :
Update the manager with a new geometry data.
- class BroadPhaseManager_IntervalTreeCollisionManager
Broad phase manager associated to hpp::fcl::IntervalTreeCollisionManager
- check((BroadPhaseManager_IntervalTreeCollisionManager)self) bool :
Check whether the base broad phase manager is aligned with the current collision_objects.
- check((BroadPhaseManager_IntervalTreeCollisionManager)self, (CollisionCallBackBase)callback) bool :
Check whether the callback is inline with *this.
- collide((BroadPhaseManager_IntervalTreeCollisionManager)self, (CollisionObject)collision_object, (CollisionCallBackBase)callback) bool :
Performs collision test between one object and all the objects belonging to the manager.
- collide((BroadPhaseManager_IntervalTreeCollisionManager)self, (CollisionCallBackBase)callback) bool :
Performs collision test for the objects belonging to the manager.
- collide((BroadPhaseManager_IntervalTreeCollisionManager)self, (BroadPhaseManager_IntervalTreeCollisionManager)other_manager, (CollisionCallBackBase)callback) bool :
Performs collision test with objects belonging to another manager.
- getCollisionObjectInflation((BroadPhaseManager_IntervalTreeCollisionManager)self) object :
Returns the inflation value related to each collision object.
- getCollisionObjectStatus((BroadPhaseManager_IntervalTreeCollisionManager)self) StdVec_Bool :
Returns the status of the collision object.
- getCollisionObjects((BroadPhaseManager_IntervalTreeCollisionManager)self) StdVec_CollisionObject
- getGeometryData((BroadPhaseManager_IntervalTreeCollisionManager)self) GeometryData :
Returns the related geometry data.
- getGeometryModel((BroadPhaseManager_IntervalTreeCollisionManager)self) GeometryModel :
Returns the related geometry model.
- getManager((BroadPhaseManager_IntervalTreeCollisionManager)self) IntervalTreeCollisionManager :
Returns the internal FCL manager
- getModel((BroadPhaseManager_IntervalTreeCollisionManager)self) Model :
Returns the related model.
- update((BroadPhaseManager_IntervalTreeCollisionManager)self[, (bool)compute_local_aabb=False]) None :
Update the manager from the current geometry positions and update the underlying FCL broad phase manager.
- update((BroadPhaseManager_IntervalTreeCollisionManager)self, (GeometryData)geom_data_new) None :
Update the manager with a new geometry data.
- class BroadPhaseManager_NaiveCollisionManager
Broad phase manager associated to hpp::fcl::NaiveCollisionManager
- check((BroadPhaseManager_NaiveCollisionManager)self) bool :
Check whether the base broad phase manager is aligned with the current collision_objects.
- check((BroadPhaseManager_NaiveCollisionManager)self, (CollisionCallBackBase)callback) bool :
Check whether the callback is inline with *this.
- collide((BroadPhaseManager_NaiveCollisionManager)self, (CollisionObject)collision_object, (CollisionCallBackBase)callback) bool :
Performs collision test between one object and all the objects belonging to the manager.
- collide((BroadPhaseManager_NaiveCollisionManager)self, (CollisionCallBackBase)callback) bool :
Performs collision test for the objects belonging to the manager.
- collide((BroadPhaseManager_NaiveCollisionManager)self, (BroadPhaseManager_NaiveCollisionManager)other_manager, (CollisionCallBackBase)callback) bool :
Performs collision test with objects belonging to another manager.
- getCollisionObjectInflation((BroadPhaseManager_NaiveCollisionManager)self) object :
Returns the inflation value related to each collision object.
- getCollisionObjectStatus((BroadPhaseManager_NaiveCollisionManager)self) StdVec_Bool :
Returns the status of the collision object.
- getCollisionObjects((BroadPhaseManager_NaiveCollisionManager)self) StdVec_CollisionObject
- getGeometryData((BroadPhaseManager_NaiveCollisionManager)self) GeometryData :
Returns the related geometry data.
- getGeometryModel((BroadPhaseManager_NaiveCollisionManager)self) GeometryModel :
Returns the related geometry model.
- getManager((BroadPhaseManager_NaiveCollisionManager)self) NaiveCollisionManager :
Returns the internal FCL manager
- getModel((BroadPhaseManager_NaiveCollisionManager)self) Model :
Returns the related model.
- update((BroadPhaseManager_NaiveCollisionManager)self[, (bool)compute_local_aabb=False]) None :
Update the manager from the current geometry positions and update the underlying FCL broad phase manager.
- update((BroadPhaseManager_NaiveCollisionManager)self, (GeometryData)geom_data_new) None :
Update the manager with a new geometry data.
- class BroadPhaseManager_SSaPCollisionManager
Broad phase manager associated to hpp::fcl::SSaPCollisionManager
- check((BroadPhaseManager_SSaPCollisionManager)self) bool :
Check whether the base broad phase manager is aligned with the current collision_objects.
- check((BroadPhaseManager_SSaPCollisionManager)self, (CollisionCallBackBase)callback) bool :
Check whether the callback is inline with *this.
- collide((BroadPhaseManager_SSaPCollisionManager)self, (CollisionObject)collision_object, (CollisionCallBackBase)callback) bool :
Performs collision test between one object and all the objects belonging to the manager.
- collide((BroadPhaseManager_SSaPCollisionManager)self, (CollisionCallBackBase)callback) bool :
Performs collision test for the objects belonging to the manager.
- collide((BroadPhaseManager_SSaPCollisionManager)self, (BroadPhaseManager_SSaPCollisionManager)other_manager, (CollisionCallBackBase)callback) bool :
Performs collision test with objects belonging to another manager.
- getCollisionObjectInflation((BroadPhaseManager_SSaPCollisionManager)self) object :
Returns the inflation value related to each collision object.
- getCollisionObjectStatus((BroadPhaseManager_SSaPCollisionManager)self) StdVec_Bool :
Returns the status of the collision object.
- getCollisionObjects((BroadPhaseManager_SSaPCollisionManager)self) StdVec_CollisionObject
- getGeometryData((BroadPhaseManager_SSaPCollisionManager)self) GeometryData :
Returns the related geometry data.
- getGeometryModel((BroadPhaseManager_SSaPCollisionManager)self) GeometryModel :
Returns the related geometry model.
- getManager((BroadPhaseManager_SSaPCollisionManager)self) SSaPCollisionManager :
Returns the internal FCL manager
- getModel((BroadPhaseManager_SSaPCollisionManager)self) Model :
Returns the related model.
- update((BroadPhaseManager_SSaPCollisionManager)self[, (bool)compute_local_aabb=False]) None :
Update the manager from the current geometry positions and update the underlying FCL broad phase manager.
- update((BroadPhaseManager_SSaPCollisionManager)self, (GeometryData)geom_data_new) None :
Update the manager with a new geometry data.
- class BroadPhaseManager_SaPCollisionManager
Broad phase manager associated to hpp::fcl::SaPCollisionManager
- check((BroadPhaseManager_SaPCollisionManager)self) bool :
Check whether the base broad phase manager is aligned with the current collision_objects.
- check((BroadPhaseManager_SaPCollisionManager)self, (CollisionCallBackBase)callback) bool :
Check whether the callback is inline with *this.
- collide((BroadPhaseManager_SaPCollisionManager)self, (CollisionObject)collision_object, (CollisionCallBackBase)callback) bool :
Performs collision test between one object and all the objects belonging to the manager.
- collide((BroadPhaseManager_SaPCollisionManager)self, (CollisionCallBackBase)callback) bool :
Performs collision test for the objects belonging to the manager.
- collide((BroadPhaseManager_SaPCollisionManager)self, (BroadPhaseManager_SaPCollisionManager)other_manager, (CollisionCallBackBase)callback) bool :
Performs collision test with objects belonging to another manager.
- getCollisionObjectInflation((BroadPhaseManager_SaPCollisionManager)self) object :
Returns the inflation value related to each collision object.
- getCollisionObjectStatus((BroadPhaseManager_SaPCollisionManager)self) StdVec_Bool :
Returns the status of the collision object.
- getCollisionObjects((BroadPhaseManager_SaPCollisionManager)self) StdVec_CollisionObject
- getGeometryData((BroadPhaseManager_SaPCollisionManager)self) GeometryData :
Returns the related geometry data.
- getGeometryModel((BroadPhaseManager_SaPCollisionManager)self) GeometryModel :
Returns the related geometry model.
- getManager((BroadPhaseManager_SaPCollisionManager)self) SaPCollisionManager :
Returns the internal FCL manager
- getModel((BroadPhaseManager_SaPCollisionManager)self) Model :
Returns the related model.
- update((BroadPhaseManager_SaPCollisionManager)self[, (bool)compute_local_aabb=False]) None :
Update the manager from the current geometry positions and update the underlying FCL broad phase manager.
- update((BroadPhaseManager_SaPCollisionManager)self, (GeometryData)geom_data_new) None :
Update the manager with a new geometry data.
- class GeometryObject
A wrapper on a collision geometry including its parent joint, parent frame, placement in parent joint’s frame.
- CreateCapsule((float)arg1, (float)arg2) GeometryObject
- clone((GeometryObject)self) GeometryObject :
Perform a deep copy of this. It will create a copy of the underlying FCL geometry.
- property disableCollision
If true, no collision or distance check will be done between the Geometry and any other geometry.
- property geometry
The FCL CollisionGeometry associated to the given GeometryObject.
- property meshColor
Color rgba of the mesh.
- property meshPath
Path to the mesh file.
- property meshScale
Scaling parameter of the mesh.
- property meshTexturePath
Path to the mesh texture file.
- property name
Name associated to the given GeometryObject.
- property overrideMaterial
Boolean that tells whether material information is stored inside the given GeometryObject.
- property parentFrame
Index of the parent frame.
- property parentJoint
Index of the parent joint.
- property placement
Position of geometry object in parent joint’s frame.
- computeBodyRadius((Model)model, (GeometryModel)geometry_model, (GeometryData)geometry_data) None :
Compute the radius of the geometry volumes attached to every joints.
- computeDistance((GeometryModel)geometry_model, (GeometryData)geometry_data, (int)pair_index) DistanceResult :
Compute the distance between the two geometry objects of a given collision pair for a GeometryModel and associated GeometryData.
- computeDistances((GeometryModel)geometry_model, (GeometryData)geometry_data) int :
Compute the distance between each collision pair for a given GeometryModel and associated GeometryData.
- computeDistances((Model)model, (Data)data, (GeometryModel)geometry_model, (GeometryData)geometry_data, (numpy.ndarray)q) int :
Update the geometry for a given configuration and compute the distance between each collision pair
- updateGeometryPlacements((Model)model, (Data)data, (GeometryModel)geometry_model, (GeometryData)geometry_data, (numpy.ndarray)q) None :
Update the placement of the collision objects according to the current configuration. The algorithm also updates the current placement of the joint in Data.
- updateGeometryPlacements((Model)model, (Data)data, (GeometryModel)geometry_model, (GeometryData)geometry_data) None :
Update the placement of the collision objects according to the current joint placement stored in data.
Contact Dynamics
- class BaumgarteCorrectorParameters
Paramaters of the Baumgarte Corrector.
- property Kd
Damping corrector value.
- property Kp
Proportional corrector value.
- class ContactCholeskyDecomposition
Contact information container for contact dynamic algorithms.
- compute((ContactCholeskyDecomposition)self, (Model)model, (Data)data, (StdVec_RigidConstraintModel)contact_models, (StdVec_RigidConstraintData)contact_datas[, (float)mu=0]) None :
Computes the Cholesky decompostion of the augmented matrix containing the KKT matrix related to the system mass matrix and the Jacobians of the contact patches contained in the vector of RigidConstraintModel named contact_models. The decomposition is regularized with a factor mu.
- compute((ContactCholeskyDecomposition)self, (Model)model, (Data)data, (StdVec_RigidConstraintModel)contact_models, (StdVec_RigidConstraintData)contact_datas, (numpy.ndarray)mus) None :
Computes the Cholesky decompostion of the augmented matrix containing the KKT matrix related to the system mass matrix and the Jacobians of the contact patches contained in the vector of RigidConstraintModel named contact_models. The decomposition is regularized with a factor mu.
- constraintDim((ContactCholeskyDecomposition)self) int :
Returns the total dimension of the constraints contained in the Cholesky factorization.
- getConstraintSparsityPattern((ContactCholeskyDecomposition)self, (int)constraint_id) numpy.ndarray :
Returns the associated sparsity of the constraints.
- getDelassusCholeskyExpression((ContactCholeskyDecomposition)self) DelassusCholeskyExpression :
Returns the Cholesky decomposition expression associated to the underlying Delassus matrix.
- getInverseMassMatrix((ContactCholeskyDecomposition)self) numpy.ndarray :
Returns the inverse of the Joint Space Inertia Matrix or “mass matrix”.
- getInverseOperationalSpaceInertiaMatrix((ContactCholeskyDecomposition)self) numpy.ndarray :
Returns the Inverse of the Operational Space Inertia Matrix resulting from the decomposition.
- getJoint1SparsityPattern((ContactCholeskyDecomposition)self, (int)constraint_id) numpy.ndarray :
Returns the associated sparsity introduced because of first joint
- getJoint2SparsityPattern((ContactCholeskyDecomposition)self, (int)constraint_id) numpy.ndarray :
Returns the associated sparsity introduces because of second joint.
- getLoopSparsityPattern((ContactCholeskyDecomposition)self, (int)constraint_id) numpy.ndarray :
Returns the sparsity of the loop constraints (indexes that connect c1 with c2)
- getMassMatrixChoeslkyDecomposition((ContactCholeskyDecomposition)arg1, (Model)self) ContactCholeskyDecomposition :
Retrieves the Cholesky decomposition of the Mass Matrix contained in the current decomposition.
- getOperationalSpaceInertiaMatrix((ContactCholeskyDecomposition)self) numpy.ndarray :
Returns the Operational Space Inertia Matrix resulting from the decomposition.
- inverse((ContactCholeskyDecomposition)self) numpy.ndarray :
Returns the inverse matrix resulting from the decomposition.
- matrix((ContactCholeskyDecomposition)self) numpy.ndarray :
Returns the matrix resulting from the decomposition.
- numContacts((ContactCholeskyDecomposition)self) int :
Returns the number of contacts associated to this decomposition.
- size((ContactCholeskyDecomposition)self) int :
Size of the decomposition.
- solve((ContactCholeskyDecomposition)self, (numpy.ndarray)matrix) numpy.ndarray :
Computes the solution of $ A x = b $ where self corresponds to the Cholesky decomposition of A.
- updateDamping((ContactCholeskyDecomposition)self, (float)mu) None :
Update the damping term on the upper left block part of the KKT matrix. The damping term should be positive.
- updateDamping((ContactCholeskyDecomposition)self, (numpy.ndarray)mus) None :
Update the damping terms on the upper left block part of the KKT matrix. The damping terms should be all positives.
- class DelassusCholeskyExpression
Delassus Cholesky expression associated to a given ContactCholeskyDecomposition object.
- cholesky((DelassusCholeskyExpression)self) ContactCholeskyDecomposition :
Returns the Constraint Cholesky decomposition associated to this DelassusCholeskyExpression.
- cols((DelassusCholeskyExpression)self) int :
Returns the number of columns.
- computeLargestEigenValue((DelassusCholeskyExpression)self[, (int)max_it=10[, (float)prec=1e-08]]) float :
Compute the largest eigen value associated to the underlying Delassus matrix.
- inverse((DelassusCholeskyExpression)self) numpy.ndarray :
Returns the inverse of the Delassus expression as a dense matrix.
- matrix((DelassusCholeskyExpression)self) numpy.ndarray :
Returns the Delassus expression as a dense matrix.
- rows((DelassusCholeskyExpression)self) int :
Returns the number of rows.
- size((DelassusCholeskyExpression)self) int :
Returns the size of the decomposition.
- solve((DelassusCholeskyExpression)self, (numpy.ndarray)mat) numpy.ndarray :
Returns the solution x of Delassus * x = mat using the current decomposition of the Delassus matrix.
- updateDamping((DelassusCholeskyExpression)self, (float)mu) None :
Add a damping term to the diagonal of the Delassus matrix. The damping term should be positive.
- updateDamping((DelassusCholeskyExpression)self, (numpy.ndarray)mus) None :
Add a damping term to the diagonal of the Delassus matrix. The damping terms should be all positive.
- class PGSSolver
Solvers Projected Gauss Siedel solver.
- getAbsoluteConvergenceResidual((PGSSolver)self) float :
Returns the value of the absolute residual value corresponding to the contact complementary conditions.
- getAbsolutePrecision((PGSSolver)self) float :
Get the absolute precision requested.
- getIterationCount((PGSSolver)self) int :
Get the number of iterations achieved by the PGS algorithm.
- getMaxIterations((PGSSolver)self) int :
Get the maximum number of iterations allowed.
- getRelativeConvergenceResidual((PGSSolver)self) float :
Returns the value of the relative residual value corresponding to the difference between two successive iterates (infinity norms).
- getRelativePrecision((PGSSolver)self) float :
Get the relative precision requested.
- setAbsolutePrecision((PGSSolver)self, (float)absolute_precision) None :
Set the absolute precision for the problem.
- setMaxIterations((PGSSolver)self, (int)max_it) None :
Set the maximum number of iterations.
- setRelativePrecision((PGSSolver)self, (float)relative_precision) None :
Set the relative precision for the problem.
- solve((PGSSolver)self, (numpy.ndarray)G, (numpy.ndarray)g, (StdVec_CoulombFrictionCone)cones, (numpy.ndarray)x[, (float)over_relax=1.0]) bool :
Solve the constrained conic problem composed of problem data (G,g,cones) and starting from the initial guess.
- class ProximalSettings
Solvers Structure containing all the settings paramters for Proximal algorithms.
- property absolute_accuracy
Absolute proximal accuracy.
- property absolute_residual
Absolute residual.
- property iter
Final number of iteration of the algorithm when it has converged or reached the maximal number of allowed iterations.
- property max_iter
Maximal number of iterations.
- property mu
Regularization parameter of the Proximal algorithms.
- property relative_accuracy
Relative proximal accuracy between two iterates.
- property relative_residual
Relatice residual between two iterates.
- class RigidConstraintData
Rigid constraint data associated to a RigidConstraintModel for contact dynamic algorithms.
- property c1Mc2
Relative displacement between the two frames.
- property contact1_acceleration_drift
Current contact drift acceleration (acceleration only due to the Coriolis and centrifugal effects) of the contact frame 1.
- property contact1_velocity
Current contact Spatial velocity of the constraint 1.
- property contact2_acceleration_drift
Current contact drift acceleration (acceleration only due to the Coriolis and centrifugal effects) of the contact frame 2.
- property contact2_velocity
Current contact Spatial velocity of the constraint 2.
- property contact_acceleration
Current contact Spatial acceleration.
- property contact_acceleration_desired
Desired contact acceleration.
- property contact_acceleration_deviation
Contact deviation from the reference acceleration (a.k.a the error).
- property contact_acceleration_error
Current contact spatial error (due to the integration step).
- property contact_force
Constraint force.
- property contact_placement_error
Current contact placement error between the two contact Frames. This corresponds to the relative placement between the two contact Frames seen as a Motion error.
- property contact_velocity_error
Current contact Spatial velocity error between the two contact Frames. This corresponds to the relative velocity between the two contact Frames.
- property extended_motion_propagators_joint1
Extended force/motion propagators for joint 1.
- property extended_motion_propagators_joint2
Extended force/motion propagators for joint 2.
- property lambdas_joint1
Extended force/motion propagators for joint 1.
- property oMc1
Placement of the constraint frame 1 with respect to the WORLD frame.
- property oMc2
Placement of the constraint frame 2 with respect to the WORLD frame.
- class RigidConstraintModel
Rigid contact model for contact dynamic algorithms.
- property colwise_joint1_sparsity
Sparsity pattern associated to joint 1.
- property colwise_joint2_sparsity
Sparsity pattern associated to joint 2.
- property colwise_span_indexes
Indexes of the columns spanned by the constraints.
- property corrector
Corrector parameters.
- createData((RigidConstraintModel)arg1) RigidConstraintData :
Create a Data object for the given model.
- property desired_contact_acceleration
Desired contact spatial acceleration.
- property desired_contact_placement
Desired contact placement.
- property desired_contact_velocity
Desired contact spatial velocity.
- property joint1_id
Index of first parent joint in the model tree.
- property joint1_placement
Relative placement with respect to the frame of joint1.
- property joint2_id
Index of second parent joint in the model tree.
- property joint2_placement
Relative placement with respect to the frame of joint2.
- property name
Name of the contact.
- property reference_frame
Reference frame where the constraint is expressed (WORLD, LOCAL_WORLD_ALIGNED or LOCAL).
- size((RigidConstraintModel)arg1) int :
Size of the constraint
- property type
Type of the contact.
- computeConstraintDynamicsDerivatives((Model)model, (Data)data, (StdVec_RigidConstraintModel)contact_models, (StdVec_RigidConstraintData)contact_datas[, (ProximalSettings)settings=ProximalSettings(1e-12, 1e-12, 0, 1)]) tuple :
Computes the derivatives of the forward dynamics with kinematic constraints (given in the list of constraint models). Assumes that constraintDynamics has been called first. See constraintDynamics for more details. This function returns the derivatives of joint acceleration (ddq) and contact forces (lambda_c) of the system with respect to q, v and tau. The output is a tuple with ddq_dq, ddq_dv, ddq_da, dlambda_dq, dlambda_dv, dlambda_da.
- computeDampedDelassusMatrixInverse((Model)arg1, (Data)model, (numpy.ndarray)data, (StdVec_RigidConstraintModel)q, (StdVec_RigidConstraintData)contact_models, (float)contact_datas[, (bool)mu=0]) numpy.ndarray :
Computes the inverse of the Delassus matrix associated to a set of given constraints.
- computeDelassusMatrix((Model)model, (Data)data, (numpy.ndarray)q, (StdVec_RigidConstraintModel)contact_models, (StdVec_RigidConstraintData)contact_datas[, (float)mu=0]) numpy.ndarray :
Computes the Delassus matrix associated to a set of given constraints.
- computeImpulseDynamicsDerivatives((Model)model, (Data)data, (StdVec_RigidConstraintModel)contact_models, (StdVec_RigidConstraintData)contact_datas[, (float)r_coeff=0[, (ProximalSettings)prox_settings=ProximalSettings(1e-12, 1e-12, 0, 1)]]) None :
Computes the impulse dynamics derivatives with contact constraints according to a given list of Contact information. impulseDynamics should have been called before.
- computeKKTContactDynamicMatrixInverse((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)constraint_jacobian[, (float)damping=0]) numpy.ndarray :
Computes the inverse of the constraint matrix [[M J^T], [J 0]].
- constraintDynamics((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)tau, (StdVec_RigidConstraintModel)contact_models, (StdVec_RigidConstraintData)contact_datas[, (ProximalSettings)prox_settings]) numpy.ndarray :
Computes the forward dynamics with contact constraints according to a given list of Contact information. When using constraintDynamics for the first time, you should call first initConstraintDynamics to initialize the internal memory used in the algorithm. This function returns joint acceleration of the system. The contact forces are stored in the list data.contact_forces.
- forwardDynamics((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)tau, (numpy.ndarray)constraint_jacobian, (numpy.ndarray)constraint_drift[, (float)damping=0]) numpy.ndarray :
Solves the constrained dynamics problem with contacts, puts the result in context::Data::ddq and return it. The contact forces are stored in data.lambda_c. Note: internally, pinocchio.computeAllTerms is called.
- forwardDynamics((Model)model, (Data)data, (numpy.ndarray)tau, (numpy.ndarray)constraint_jacobian, (numpy.ndarray)constraint_drift[, (float)damping=0]) numpy.ndarray :
Solves the forward dynamics problem with contacts, puts the result in context::Data::ddq and return it. The contact forces are stored in data.lambda_c. Note: this function assumes that pinocchio.computeAllTerms has been called first.
- getConstraintJacobian((Model)model, (Data)data, (RigidConstraintModel)contact_model, (RigidConstraintData)contact_data) numpy.ndarray :
Computes the kinematic Jacobian associatied to a given constraint model.
- getConstraintsJacobian((Model)model, (Data)data, (StdVec_RigidConstraintModel)contact_models, (StdVec_RigidConstraintData)contact_datas) numpy.ndarray :
Computes the kinematic Jacobian associatied to a given set of constraint models.
- getKKTContactDynamicMatrixInverse((Model)model, (Data)data, (numpy.ndarray)constraint_jacobian) numpy.ndarray :
- Computes the inverse of the constraint matrix [[M Jt], [J 0]].
forwardDynamics or impulseDynamics must have been called first.
Note: the constraint Jacobian should be the same that was provided to forwardDynamics or impulseDynamics.
- impulseDynamics((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v_before, (numpy.ndarray)constraint_jacobian[, (float)restitution_coefficient=0[, (float)damping=0]]) numpy.ndarray :
Solves the impact dynamics problem with contacts, store the result in context::Data::dq_after and return it. The contact impulses are stored in data.impulse_c. Note: internally, pinocchio.crba is called.
- impulseDynamics((Model)model, (Data)data, (numpy.ndarray)v_before, (numpy.ndarray)constraint_jacobian[, (float)restitution_coefficient=0[, (float)damping=0]]) numpy.ndarray :
Solves the impact dynamics problem with contacts, store the result in context::Data::dq_after and return it. The contact impulses are stored in data.impulse_c. Note: this function assumes that pinocchio.crba has been called first.
- impulseDynamics((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (StdVec_RigidConstraintModel)contact_models, (StdVec_RigidConstraintData)contact_datas[, (float)r_coeff=0[, (ProximalSettings)prox_settings=ProximalSettings(1e-12, 1e-12, 0, 1)]]) numpy.ndarray :
Computes the impulse dynamics with contact constraints according to a given list of Contact information. When using impulseDynamics for the first time, you should call first initConstraintDynamics to initialize the internal memory used in the algorithm. This function returns the after-impulse velocity of the system. The impulses acting on the contacts are stored in the list data.contact_forces.
- initConstraintDynamics((Model)model, (Data)data, (StdVec_RigidConstraintModel)contact_models) None :
This function allows to allocate the memory before hand for contact dynamics algorithms. This allows to avoid online memory allocation when running these algorithms.
Dynamics
- aba((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)tau) numpy.ndarray :
Compute ABA, store the result in
data.ddq
and return it.- Parameters:
model – Model of the kinematic tree
data – Data related to the kinematic tree
q – joint configuration (size
model.nq
)tau – joint velocity (size
model.nv
)v – joint torque (size
model.nv
)
- aba((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)tau, (StdVec_Force)fext) numpy.ndarray :
Compute ABA with external forces, store the result in
data.ddq
and return it.- Parameters:
model – Model of the kinematic tree
data – Data related to the kinematic tree
q – joint configuration (size
model.nq
)v – joint velocity (size
model.nv
)tau – joint torque (size
model.nv
)fext – vector of external forces expressed in the local frame of the joint (size
model.njoints
)
- computeABADerivatives((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)tau) tuple :
Computes the ABA derivatives, store the result in
data.ddq_dq
,data.ddq_dv
anddata.Minv
(akaddq_dtau
) which correspond to the partial derivatives of the joint acceleration vector output with respect to the joint configuration, velocity and torque vectors.- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size
model.nq
)v – the joint velocity vector (size
model.nv
)tau – the joint torque vector (size
model.nv
)
- Returns:
(
ddq_dq
,ddq_dv
,ddq_da
)
- computeABADerivatives((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)tau, (StdVec_Force)fext) tuple :
Computes the ABA derivatives with external contact foces, store the result in
data.ddq_dq
,data.ddq_dv
anddata.Minv
(akaddq_dtau
) which correspond to the partial derivatives of the acceleration output with respect to the joint configuration, velocity and torque vectors.- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size
model.nq
)v – the joint velocity vector (size
model.nv
)tau – the joint torque vector (size
model.nv
)fext – list of external forces expressed in the local frame of the joints (size
model.njoints
)
- Returns:
(
ddq_dq
,ddq_dv
,ddq_da
)
- computeABADerivatives((Model)model, (Data)data) tuple :
Computes the ABA derivatives, store the result in
data.ddq_dq
,data.ddq_dv
anddata.Minv
which correspond to the partial derivatives of the joint acceleration vector output with respect to the joint configuration, velocity and torque vectors. By calling this function, the user assumes that pinocchio.optimized.aba has been called first, allowing to significantly reduce the computation timings by not recalculating intermediate results.
- computeABADerivatives((Model)model, (Data)data, (StdVec_Force)fext) tuple :
Computes the ABA derivatives, store the result in
data.ddq_dq
,data.ddq_dv
anddata.Minv
which correspond to the partial derivatives of the joint acceleration vector output with respect to the joint configuration, velocity and torque vectors. By calling this function, the user assumes that pinocchio.optimized.aba has been called first, allowing to significantly reduce the computation timings by not recalculating intermediate results.
- computeCoriolisMatrix((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v) numpy.ndarray :
Compute the Coriolis Matrix C(q,v) of the Lagrangian dynamics, store the result in data.C and return it.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
v – the joint velocity vector (size model.nv)
- computeGeneralizedGravity((Model)model, (Data)data, (numpy.ndarray)q) numpy.ndarray :
Compute the generalized gravity contribution g(q) of the Lagrangian dynamics, store the result in data.g and return it.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
- computeGeneralizedGravityDerivatives((Model)model, (Data)data, (numpy.ndarray)q) numpy.ndarray :
Computes the partial derivative of the generalized gravity contribution with respect to the joint configuration.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
- Returns:
dtau_statique_dq
- computeMinverse((Model)model, (Data)data, (numpy.ndarray)q) numpy.ndarray :
Computes the inverse of the joint space inertia matrix using an extension of the Articulated Body algorithm.
The result is stored in
data.Minv
. :param model: Model of the kinematic tree :param data: Data related to the kinematic tree :param q: joint configuration (sizemodel.nq
)
- computeMinverse((Model)model, (Data)data) numpy.ndarray :
Computes the inverse of the joint space inertia matrix using an extension of the Articulated Body algorithm. The result is stored in
data.Minv
. Remarks: pinocchio.aba should have been called first.- Parameters:
model – Model of the kinematic tree
data – Data related to the kinematic tree
- computeRNEADerivatives((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)a) tuple :
Computes the RNEA partial derivatives, store the result in data.dtau_dq, data.dtau_dv and data.M (aka dtau_da) which correspond to the partial derivatives of the torque output with respect to the joint configuration, velocity and acceleration vectors.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
v – the joint velocity vector (size model.nv)
a – the joint acceleration vector (size model.nv)
- Returns:
(dtau_dq, dtau_dv, dtau_da)
- computeRNEADerivatives((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)a, (StdVec_Force)fext) tuple :
Computes the RNEA partial derivatives with external contact foces, store the result in data.dtau_dq, data.dtau_dv and data.M (aka dtau_da) which correspond to the partial derivatives of the torque output with respect to the joint configuration, velocity and acceleration vectors.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
v – the joint velocity vector (size model.nv)
a – the joint acceleration vector (size model.nv)
fext – list of external forces expressed in the local frame of the joints (size model.njoints)
- Returns:
(dtau_dq, dtau_dv, dtau_da)
- computeStaticTorque((Model)model, (Data)data, (numpy.ndarray)q, (StdVec_Force)fext) numpy.ndarray :
Computes the generalized static torque contribution g(q) - J.T f_ext of the Lagrangian dynamics, store the result in data.tau and return it.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
fext – list of external forces expressed in the local frame of the joints (size model.njoints)
- computeStaticTorqueDerivatives((Model)model, (Data)data, (numpy.ndarray)q, (StdVec_Force)fext) numpy.ndarray :
Computes the partial derivative of the generalized gravity and external forces contributions (a.k.a static torque vector) with respect to the joint configuration.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
fext – list of external forces expressed in the local frame of the joints (size model.njoints)
- Returns:
dtau_statique_dq
- getCoriolisMatrix((Model)model, (Data)data) numpy.ndarray :
Retrives the Coriolis Matrix C(q,v) of the Lagrangian dynamics after calling one of the derivative algorithms, store the result in data.C and return it.
- Parameters:
model – model of the kinematic tree
data – data related to the model
- nonLinearEffects((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v) numpy.ndarray :
Compute the Non Linear Effects (coriolis, centrifugal and gravitational effects), store the result in Data and return it.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
v – the joint velocity vector (size model.nv)
- rnea((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)a) numpy.ndarray :
Compute the RNEA, store the result in Data and return it.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
v – the joint velocity vector (size model.nv)
a – the joint acceleration vector (size model.nv)
- rnea((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)a, (StdVec_Force)fext) numpy.ndarray :
Compute the RNEA with external forces, store the result in Data and return it.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
v – the joint velocity vector (size model.nv)
a – the joint acceleration vector (size model.nv)
fext – list of external forces expressed in the local frame of the joints (size model.njoints)
Energy
- computeKineticEnergy((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v) float :
Computes the forward kinematics and the kinematic energy of the system for the given joint configuration and velocity given as input. The result is accessible through data.kinetic_energy.
- computeKineticEnergy((Model)model, (Data)data) float :
Computes the kinematic energy of the system for the given joint placement and velocity stored in data. The result is accessible through data.kinetic_energy.
- computeMechanicalEnergy((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v) float :
Computes the forward kinematics and the kinematic energy of the system for the given joint configuration and velocity given as input. The result is accessible through data.mechanical_energy. A byproduct of this function is the computation of both data.kinetic_energy and data.potential_energy too.
- computeMechanicalEnergy((Model)model, (Data)data) float :
Computes the mechanical energy of the system for the given joint placement and velocity stored in data. The result is accessible through data.mechanical_energy. A byproduct of this function is the computation of both data.kinetic_energy and data.potential_energy too.
- computePotentialEnergy((Model)model, (Data)data, (numpy.ndarray)q) float :
Computes the potential energy of the system for the given the joint configuration given as input. The result is accessible through data.potential_energy.
- computePotentialEnergy((Model)model, (Data)data) float :
Computes the potential energy of the system for the given joint placement stored in data. The result is accessible through data.potential_energy.
General
- computeAllTerms((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v) None :
Compute all the terms M, non linear effects, center of mass quantities, centroidal quantities and Jacobians inin the same loop and store the results in data. This algorithm is equivalent to calling:
forwardKinematics
crba
nonLinearEffects
computeJointJacobians
centerOfMass
jacobianCenterOfMass
ccrba
computeKineticEnergy
computePotentialEnergy
computeGeneralizedGravity
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size
model.nq
)v – the joint velocity vector (size
model.nv
)
Jacobian
- computeJointJacobian((Model)model, (Data)data, (numpy.ndarray)q, (int)joint_id) numpy.ndarray :
Computes the Jacobian of a specific joint frame expressed in the local frame of the joint according to the given input configuration.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
joint_id – index of the joint
- computeJointJacobians((Model)model, (Data)data, (numpy.ndarray)q) numpy.ndarray :
Computes the full model Jacobian, i.e. the stack of all the motion subspaces expressed in the coordinate world frame. The result is accessible through data.J. This function computes also the forward kinematics of the model.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
- computeJointJacobians((Model)model, (Data)data) numpy.ndarray :
Computes the full model Jacobian, i.e. the stack of all motion subspace expressed in the world frame. The result is accessible through data.J. This function assumes that forward kinematics (pinocchio.forwardKinematics) has been called first.
- Parameters:
model – model of the kinematic tree
data – data related to the model
- computeJointJacobiansTimeVariation((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v) numpy.ndarray :
Computes the full model Jacobian variations with respect to time. It corresponds to dJ/dt which depends both on q and v. It also computes the joint Jacobian of the model (similar to computeJointJacobians).The result is accessible through data.dJ and data.J.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
v – the joint velocity vector (size model.nv)
- getJointJacobian((Model)model, (Data)data, (int)joint_id, (ReferenceFrame)reference_frame) numpy.ndarray :
Computes the jacobian of a given given joint according to the given entries in data. If reference_frame is set to LOCAL, it returns the Jacobian expressed in the local coordinate system of the joint. If reference_frame is set to LOCAL_WORLD_ALIGNED, it returns the Jacobian expressed in the coordinate system of the frame centered on the joint, but aligned with the WORLD axes. If reference_frame is set to WORLD, it returns the Jacobian expressed in the coordinate system of the frame associated to the WORLD.
- Parameters:
model – model of the kinematic tree
data – data related to the model
joint_id – index of the joint
reference_frame – reference frame in which the resulting derivatives are expressed
- getJointJacobianTimeVariation((Model)model, (Data)data, (int)joint_id, (ReferenceFrame)reference_frame) numpy.ndarray :
Computes the Jacobian time variation of a specific joint expressed in the requested frame provided by the value of reference_frame.You have to call computeJointJacobiansTimeVariation first. This function also computes the full model Jacobian contained in data.J. If reference_frame is set to LOCAL, it returns the Jacobian expressed in the local coordinate system of the joint. If reference_frame is set to LOCAL_WORLD_ALIGNED, it returns the Jacobian expressed in the coordinate system of the frame centered on the joint, but aligned with the WORLD axes. If reference_frame is set to WORLD, it returns the Jacobian expressed in the coordinate system of the frame associated to the WORLD.
- Parameters:
model – model of the kinematic tree
data – data related to the model
joint_id – index of the joint
reference_frame – reference frame in which the resulting derivatives are expressed
Kinematics
- computeForwardKinematicsDerivatives((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)a) None :
Computes all the terms required to compute the derivatives of the placement, spatial velocity and acceleration for any joint of the model. The results are stored in data.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
v – the joint velocity vector (size model.nv)
a – the joint acceleration vector (size model.nv)
- forwardKinematics((Model)model, (Data)data, (numpy.ndarray)q) None :
Compute the global placements of all the joints of the kinematic tree and store the results in data.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
- forwardKinematics((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v) None :
Compute the global placements and local spatial velocities of all the joints of the kinematic tree and store the results in data.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
v – the joint velocity vector (size model.nv)
- forwardKinematics((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)a) None :
Compute the global placements, local spatial velocities and spatial accelerations of all the joints of the kinematic tree and store the results in data.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
v – the joint velocity vector (size model.nv)
a – the joint acceleration vector (size model.nv)
- getAcceleration((Model)model, (Data)data, (int)joint_id[, (ReferenceFrame)reference_frame=pinocchio.pinocchio_pywrap_default.ReferenceFrame.LOCAL]) Motion :
Returns the spatial acceleration of the joint expressed in the coordinate system given by reference_frame. forwardKinematics(model,data,q,v,a) should be called first to compute the joint spatial acceleration stored in data.a .
- getCenterOfMassVelocityDerivatives((Model)model, (Data)data) numpy.ndarray :
Computes the partial derivaties of the center of mass velocity with respect to the joint configuration. You must first call computeAllTerms(model,data,q,v) or centerOfMass(model,data,q,v) before calling this function.
- Parameters:
model – model of the kinematic tree
data – data related to the model
- getClassicalAcceleration((Model)model, (Data)data, (int)joint_id[, (ReferenceFrame)reference_frame=pinocchio.pinocchio_pywrap_default.ReferenceFrame.LOCAL]) Motion :
Returns the “classical” acceleration of the joint expressed in the coordinate system given by reference_frame. forwardKinematics(model,data,q,v,a) should be called first to compute the joint spatial acceleration stored in data.a .
- getJointAccelerationDerivatives((Model)model, (Data)data, (int)joint_id, (ReferenceFrame)reference_frame) tuple :
Computes the partial derivatives of the spatial acceleration of a given joint with respect to the joint configuration, velocity and acceleration and returns them as a tuple. The partial derivatives can be either expressed in the LOCAL frame of the joint, in the LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of reference_frame. You must first call computeForwardKinematicsDerivatives before calling this function.
- Parameters:
model – model of the kinematic tree
data – data related to the model
joint_id – index of the joint
reference_frame – reference frame in which the resulting derivatives are expressed
- getJointVelocityDerivatives((Model)model, (Data)data, (int)joint_id, (ReferenceFrame)reference_frame) tuple :
Computes the partial derivatives of the spatial velocity of a given joint with respect to the joint configuration and velocity and returns them as a tuple. The partial derivatives can be either expressed in the LOCAL frame of the joint, in the LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of reference_frame. You must first call computeForwardKinematicsDerivatives before calling this function.
- Parameters:
model – model of the kinematic tree
data – data related to the model
joint_id – index of the joint
reference_frame – reference frame in which the resulting derivatives are expressed
- getPointClassicAccelerationDerivatives((Model)model, (Data)data, (int)joint_id, (SE3)placement, (ReferenceFrame)reference_frame) tuple :
Computes the partial derivatives of the classic acceleration of a point given by its placement information w.r.t. the joint frame and returns them as a tuple. The partial derivatives can be either expressed in the LOCAL frame of the joint, in the LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of reference_frame. You must first call computeForwardKinematicsDerivatives before calling this function.
- Parameters:
model – model of the kinematic tree
data – data related to the model
joint_id – index of the joint
placement – relative placement of the point w.r.t. the joint frame
reference_frame – reference frame in which the resulting derivatives are expressed
- getPointVelocityDerivatives((Model)model, (Data)data, (int)joint_id, (SE3)placement, (ReferenceFrame)reference_frame) tuple :
Computes the partial derivatives of the velocity of a point given by its placement information w.r.t. the joint frame and returns them as a tuple. The partial derivatives can be either expressed in the LOCAL frame of the joint, in the LOCAL_WORLD_ALIGNED frame or in the WORLD coordinate frame depending on the value of reference_frame. You must first call computeForwardKinematicsDerivatives before calling this function.
- Parameters:
model – model of the kinematic tree
data – data related to the model
joint_id – index of the joint
placement – relative placement of the point w.r.t. the joint frame
reference_frame – reference frame in which the resulting derivatives are expressed
- getVelocity((Model)model, (Data)data, (int)joint_id[, (ReferenceFrame)reference_frame=pinocchio.pinocchio_pywrap_default.ReferenceFrame.LOCAL]) Motion :
Returns the spatial velocity of the joint expressed in the coordinate system given by reference_frame. forwardKinematics(model,data,q,v[,a]) should be called first to compute the joint spatial velocity stored in data.v
- updateGlobalPlacements((Model)model, (Data)data) None :
Updates the global placements of all joint frames of the kinematic tree and store the results in data according to the relative placements of the joints.
- Parameters:
model – model of the kinematic tree
data – data related to the model
Mass
- centerOfMass((Model)model, (Data)data, (numpy.ndarray)q[, (bool)compute_subtree_coms=True]) numpy.ndarray :
Compute the center of mass, putting the result in
context.Data
and return it.Ifcompute_subtree_coms
is True, the algorithm also computes the center of mass of the subtrees.
- centerOfMass((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v[, (bool)compute_subtree_coms=True]) numpy.ndarray :
Computes the center of mass position and velocity by storing the result in
context.Data
. It returns the center of mass position expressed in theWORLD
frame. Ifcompute_subtree_coms
is True, the algorithm also computes the center of mass of the subtrees.
- centerOfMass((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)a[, (bool)compute_subtree_coms=True]) numpy.ndarray :
Computes the center of mass position, velocity and acceleration by storing the result in
context.Data
. It returns the center of mass position expressed in theWORLD
frame. Ifcompute_subtree_coms
is True, the algorithm also computes the center of mass of the subtrees.
- centerOfMass((Model)model, (Data)data, (int)kinematic_level[, (bool)compute_subtree_coms=True]) None :
Computes the center of mass position, velocity and acceleration of a given model according to the current kinematic values contained in data and the requested kinematic_level. If
kinematic_level = 0
, computes the CoM position.If
kinematic_level = 1
, also computes the CoM velocity.If
kinematic_level = 2
, it also computes the CoM acceleration.
- centerOfMass((Model)model, (Data)data, (KinematicLevel)kinematic_level[, (bool)compute_subtree_coms=True]) numpy.ndarray :
Computes the center of mass position, velocity or acceleration of a given model according to the current kinematic values contained in data and the requested kinematic_level. If
kinematic_level = POSITION
, computes the CoM position, ifkinematic_level = VELOCITY
, also computes the CoM velocity and ifkinematic_level = ACCELERATION
, it also computes the CoM acceleration. Ifcompute_subtree_coms
is True, the algorithm also computes the center of mass of the subtrees.
- centerOfMass((Model)model, (Data)data[, (bool)compute_subtree_coms=True]) numpy.ndarray :
Computes the center of mass position, velocity and acceleration of a given model according to the current kinematic values contained in data. If
compute_subtree_coms
is True, the algorithm also computes the center of mass of the subtrees.
- computeSubtreeMasses((Model)model, (Data)data) None :
Compute the mass of each kinematic subtree and store it in the vector
data.mass
.
- computeTotalMass((Model)model) float :
Compute the total mass of the model and return it.
- computeTotalMass((Model)model, (Data)data) float :
Compute the total mass of the model, put it in
data.mass[0]
and return it.
- getJacobianSubtreeCenterOfMass((Model)model, (Data)data, (int)subtree_root_joint_id) numpy.ndarray :
Get the Jacobian of the CoM of the given subtree expressed in the
WORLD
frame, according to the given entries indata
. It assumes thatjacobianCenterOfMass
has been called first.
- jacobianCenterOfMass((Model)model, (Data)data, (numpy.ndarray)q[, (bool)compute_subtree_coms=True]) numpy.ndarray :
Computes the Jacobian of the center of mass, puts the result in
context.Data
and return it. Ifcompute_subtree_coms
is True, the algorithm also computes the center of mass of the subtrees.
- jacobianCenterOfMass((Model)model, (Data)data[, (bool)compute_subtree_coms=True]) numpy.ndarray :
Computes the Jacobian of the center of mass, puts the result in
context.Data
and return it. Ifcompute_subtree_coms
is True, the algorithm also computes the center of mass of the subtrees.
- jacobianSubtreeCenterOfMass((Model)model, (Data)data, (numpy.ndarray)q, (int)subtree_root_joint_id) numpy.ndarray :
Computes the Jacobian of the CoM of the given subtree (
subtree_root_joint_id
) expressed in theWORLD
frame, according to the given joint configuration.
- jacobianSubtreeCenterOfMass((Model)model, (Data)data, (int)subtree_root_joint_id) numpy.ndarray :
Computes the Jacobian of the CoM of the given subtree (
subtree_root_joint_id
) expressed in theWORLD
frame, according to the given entries indata
.
- jacobianSubtreeCoMJacobian((Model)model, (Data)data, (numpy.ndarray)q, (int)subtree_root_joint_id) numpy.ndarray :
Computes the Jacobian of the CoM of the given subtree expressed in the
WORLD
frame, according to the given joint configuration.
- jacobianSubtreeCoMJacobian((Model)model, (Data)data, (int)subtree_root_joint_id) numpy.ndarray :
Computes the Jacobian of the CoM of the given subtree expressed in the
WORLD
frame, according to the given entries indata
.
Regressor
- bodyRegressor((Motion)velocity, (Motion)acceleration) numpy.ndarray :
Computes the regressor for the dynamic parameters of a single rigid body. The result is such that Ia + v x Iv = bodyRegressor(v,a) * I.toDynamicParameters()
- Parameters:
velocity – spatial velocity of the rigid body
acceleration – spatial acceleration of the rigid body
- computeFrameKinematicRegressor((Model)model, (Data)data, (int)frame_id, (ReferenceFrame)reference_frame) numpy.ndarray :
Computes the kinematic regressor that links the joint placement variations of the whole kinematic tree to the placement variation of the frame given as input.
- Parameters:
model – model of the kinematic tree
data – data related to the model
frame_id – index of the frame
reference_frame – reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or WORLD)
- computeJointKinematicRegressor((Model)model, (Data)data, (int)joint_id, (ReferenceFrame)reference_frame, (SE3)placement) numpy.ndarray :
Computes the kinematic regressor that links the joint placements variations of the whole kinematic tree to the placement variation of the frame rigidly attached to the joint and given by its placement w.r.t. to the joint frame.
- Parameters:
model – model of the kinematic tree
data – data related to the model
joint_id – index of the joint
reference_frame – reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or WORLD)
placement – relative placement to the joint frame
- computeJointKinematicRegressor((Model)model, (Data)data, (int)joint_id, (ReferenceFrame)reference_frame) numpy.ndarray :
Computes the kinematic regressor that links the joint placement variations of the whole kinematic tree to the placement variation of the joint given as input.
- Parameters:
model – model of the kinematic tree
data – data related to the model
joint_id – index of the joint
reference_frame – reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or WORLD)
- computeJointTorqueRegressor((Model)model, (Data)data, (numpy.ndarray)q, (numpy.ndarray)v, (numpy.ndarray)a) numpy.ndarray :
Compute the joint torque regressor that links the joint torque to the dynamic parameters of each link according to the current the robot motion, store the result in context::Data and return it.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
v – the joint velocity vector (size model.nv)
a – the joint acceleration vector (size model.nv)
- computeStaticRegressor((Model)model, (Data)data, (numpy.ndarray)q) numpy.ndarray :
Compute the static regressor that links the inertia parameters of the system to its center of mass position, store the result in context::Data and return it.
- Parameters:
model – model of the kinematic tree
data – data related to the model
q – the joint configuration vector (size model.nq)
- frameBodyRegressor((Model)model, (Data)data, (int)frame_id) numpy.ndarray :
Computes the regressor for the dynamic parameters of a rigid body attached to a given frame. This algorithm assumes RNEA has been run to compute the acceleration and gravitational effects.
- Parameters:
model – model of the kinematic tree
data – data related to the model
frame_id – index of the frame
- jointBodyRegressor((Model)model, (Data)data, (int)joint_id) numpy.ndarray :
Compute the regressor for the dynamic parameters of a rigid body attached to a given joint. This algorithm assumes RNEA has been run to compute the acceleration and gravitational effects.
- Parameters:
model – model of the kinematic tree
data – data related to the model
joint_id – index of the joint