Namespaces | Functions
center-of-mass.hpp File Reference
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/multibody/data.hpp"
#include "pinocchio/algorithm/center-of-mass.hxx"
Include dependency graph for center-of-mass.hpp:

Go to the source code of this file.

Namespaces

 pinocchio
 Main pinocchio namespace.
 

Functions

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType >
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & pinocchio::centerOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const bool computeSubtreeComs=true)
 Computes the center of mass position of a given model according to a particular joint configuration. The result is accessible through data.com[0] for the full body com and data.com[i] for the subtree supported by joint i (expressed in the joint i frame). More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType >
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & pinocchio::centerOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const bool computeSubtreeComs=true)
 Computes the center of mass position and velocity of a given model according to a particular joint configuration and velocity. The result is accessible through data.com[0], data.vcom[0] for the full body com position and velocity. And data.com[i] and data.vcom[i] for the subtree supported by joint i (expressed in the joint i frame). More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 >
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & pinocchio::centerOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, const bool computeSubtreeComs=true)
 Computes the center of mass position, velocity and acceleration of a given model according to a particular joint configuration, velocity and acceleration. The result is accessible through data.com[0], data.vcom[0], data.acom[0] for the full body com position, velocity and acceleation. And data.com[i], data.vcom[i] and data.acom[i] for the subtree supported by joint i (expressed in the joint i frame). More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & pinocchio::centerOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, KinematicLevel kinematic_level, const bool computeSubtreeComs=true)
 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. The result is accessible through data.com[0], data.vcom[0] and data.acom[0] for the full body com position and velocity. And data.com[i] and data.vcom[i] for the subtree supported by joint i (expressed in the joint i frame). More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
PINOCCHIO_DEPRECATED void pinocchio::centerOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, int kinematic_level, const bool computeSubtreeComs=true)
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & pinocchio::centerOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const bool computeSubtreeComs=true)
 Computes the center of mass position, velocity and acceleration of a given model according to the current kinematic values contained in data. The result is accessible through data.com[0], data.vcom[0] and data.acom[0] for the full body com position and velocity. And data.com[i] and data.vcom[i] for the subtree supported by joint i (expressed in the joint i frame). More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
void pinocchio::computeSubtreeMasses (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
 Compute the mass of each kinematic subtree and store it in data.mass. The element mass[0] corresponds to the total mass of the model. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
Scalar pinocchio::computeTotalMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model)
 Compute the total mass of the model and return it. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
Scalar pinocchio::computeTotalMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
 Compute the total mass of the model, put it in data.mass[0] and return it. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & pinocchio::getComFromCrba (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
 Extracts the center of mass position from the joint space inertia matrix (also called the mass matrix). More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & pinocchio::getJacobianComFromCrba (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
 Extracts both the jacobian of the center of mass (CoM), the total mass of the system and the CoM position from the joint space inertia matrix (also called the mass matrix). The results are accessible through data.Jcom, data.mass[0] and data.com[0] and are both expressed in the world frame. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix3xLike >
void pinocchio::getJacobianSubtreeCenterOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex &rootSubtreeId, const Eigen::MatrixBase< Matrix3xLike > &res)
 Retrieves the Jacobian of the center of mass of the given subtree according to the current value stored in data. It assumes that pinocchio::jacobianCenterOfMass has been called first with computeSubtreeComs equals to true. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType >
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & pinocchio::jacobianCenterOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const bool computeSubtreeComs=true)
 Computes both the jacobian and the the center of mass position of a given model according to a particular joint configuration. The results are accessible through data.Jcom and data.com[0] and are both expressed in the world frame. In addition, the algorithm also computes the Jacobian of all the joints (. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & pinocchio::jacobianCenterOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const bool computeSubtreeComs=true)
 Computes both the jacobian and the the center of mass position of a given model according to the current value stored in data. It assumes that forwardKinematics has been called first. The results are accessible through data.Jcom and data.com[0] and are both expressed in the world frame. In addition, the algorithm also computes the Jacobian of all the joints (. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename Matrix3xLike >
void pinocchio::jacobianSubtreeCenterOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const JointIndex &rootSubtreeId, const Eigen::MatrixBase< Matrix3xLike > &res)
 Computes the Jacobian of the center of mass of the given subtree according to a particular joint configuration. In addition, the algorithm also computes the Jacobian of all the joints (. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix3xLike >
void pinocchio::jacobianSubtreeCenterOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex &rootSubtreeId, const Eigen::MatrixBase< Matrix3xLike > &res)
 Computes the Jacobian of the center of mass of the given subtree according to the current value stored in data. It assumes that forwardKinematics has been called first. More...
 


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:05