18 #ifndef __se3_compute_all_terms_hpp__ 19 #define __se3_compute_all_terms_hpp__ 21 #include "pinocchio/multibody/visitor.hpp" 22 #include "pinocchio/multibody/model.hpp" 23 #include "pinocchio/multibody/data.hpp" 24 #include "pinocchio/spatial/act-on-set.hpp" 25 #include "pinocchio/algorithm/center-of-mass.hpp" 26 #include "pinocchio/algorithm/energy.hpp" 27 #include "pinocchio/algorithm/check.hpp" 51 const Eigen::VectorXd & q,
52 const Eigen::VectorXd & v);
63 typedef boost::fusion::vector<
const se3::Model &,
65 const Eigen::VectorXd &,
66 const Eigen::VectorXd &
71 template<
typename Jo
intModel>
74 const se3::Model & model,
76 const Eigen::VectorXd & q,
77 const Eigen::VectorXd & v)
79 using namespace Eigen;
82 const Model::JointIndex & i = (Model::JointIndex) jmodel.id();
83 const Model::JointIndex & parent = model.
parents[i];
85 jmodel.calc(jdata.derived(),q,v);
92 data.
v[i] = jdata.v();
97 data.
v[i] += data.
liMi[i].actInv(data.
v[parent]);
102 jmodel.jointCols(data.
J) = data.
oMi[i].act(jdata.S());
104 data.
a_gf[i] = data.
a[i] = jdata.c() + (data.
v[i] ^ jdata.v());
106 data.
a[i] += data.
liMi[i].actInv(data.
a[parent]);
113 const double mass = model.
inertias[i].mass();
114 const SE3::Vector3 & lever = model.
inertias[i].lever();
116 data.
com[i] = mass * lever;
119 data.
vcom[i] = mass * (data.
v[i].angular().cross(lever) + data.
v[i].linear());
126 typedef boost::fusion::vector<
const Model &,
131 template<
typename Jo
intModel>
144 const Model::JointIndex & i = (Model::JointIndex) jmodel.id();
145 const Model::JointIndex & parent = model.
parents[i];
146 const SE3 & oMi = data.
oMi[i];
149 jmodel.jointCols(data.
Fcrb[i]) = data.
Ycrb[i] * jdata.S();
152 data.
M.block(jmodel.idx_v(),jmodel.idx_v(),jmodel.nv(),data.
nvSubtree[i])
153 = jdata.S().transpose()*data.
Fcrb[i].middleCols(jmodel.idx_v(),data.
nvSubtree[i]);
156 jmodel.jointVelocitySelector(data.
nle) = jdata.S().transpose()*data.
f[i];
163 Eigen::Block<typename Data::Matrix6x> jF
164 = data.
Fcrb[parent].block(0,jmodel.idx_v(),6,data.
nvSubtree[i]);
165 Eigen::Block<typename Data::Matrix6x> iF
167 forceSet::se3Action(data.
liMi[i], iF, jF);
169 data.
f[parent] += data.
liMi[i].act(data.
f[i]);
173 const SE3 & liMi = data.
liMi[i];
175 data.
com[parent] += (liMi.rotation()*data.
com[i]
176 + data.
mass[i] * liMi.translation());
178 SE3::Vector3 com_in_world (oMi.rotation() * data.
com[i] + data.
mass[i] * oMi.translation());
180 data.
vcom[parent] += liMi.rotation()*data.
vcom[i];
186 ColBlock Jcols = jmodel.jointCols(data.
J);
188 if( JointModel::NV==1 )
189 data.
Jcom.col(jmodel.idx_v())
190 = data.
mass[i] * Jcols.template topLeftCorner<3,1>()
191 - com_in_world.cross(Jcols.template bottomLeftCorner<3,1>()) ;
193 jmodel.jointCols(data.
Jcom)
194 = data.
mass[i] * Jcols.template topRows<3>()
195 -
skew(com_in_world) * Jcols.template bottomRows<3>();
205 const Eigen::VectorXd & q,
206 const Eigen::VectorXd & v)
208 assert(model.
check(data) &&
"data is not consistent with model.");
214 data.
com[0].setZero ();
215 data.
vcom[0].setZero ();
217 for(Model::JointIndex i=1;i<(Model::JointIndex) model.
njoints;++i)
220 CATForwardStep::ArgsType(model,data,q,v));
223 for(Model::JointIndex i=(Model::JointIndex)(model.
njoints-1);i>0;--i)
226 CATBackwardStep::ArgsType(model,data));
244 #endif // ifndef __se3_compute_all_terms_hpp__
container::aligned_vector< Motion > a
Vector of joint accelerations expressed at the centers of the joints.
Matrix3x Jcom
Jacobien of center of mass.
container::aligned_vector< Eigen::Vector3d > vcom
Vector of subtree center of mass linear velocities expressed in the root joint of the subtree...
container::aligned_vector< SE3 > jointPlacements
Placement (SE3) of the input of joint i regarding to the parent joint output li.
std::vector< int > nvSubtree
Dimension of the subtree motion space (for CRBA)
void computeAllTerms(const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v)
Computes efficiently all the terms needed for dynamic simulation. It is equivalent to the call at the...
double potentialEnergy(const Model &model, Data &data, const Eigen::VectorXd &q, const bool update_kinematics=true)
Computes the potential energy of the system, i.e. the potential energy linked to the gravity field...
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Eigen::Matrix< double, 6, Eigen::Dynamic > Matrix6x
The 6d jacobian type (temporary)
JointModelVector joints
Model of joint i, encapsulated in a JointModelAccessor.
container::aligned_vector< Inertia > Ycrb
Vector of sub-tree composite rigid body inertias, i.e. the apparent inertia of the subtree supported ...
double kineticEnergy(const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const bool update_kinematics=true)
Computes the kinetic energy of the system. The result is accessible through data.kinetic_energy.
void skew(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector, i.e. the antisymmetric matrix representation o...
Matrix6x J
Jacobian of joint placements.
std::vector< JointIndex > parents
Joint parent of joint i, denoted li (li==parents[i]).
container::aligned_vector< Matrix6x > Fcrb
Spatial forces set, used in CRBA and CCRBA.
Eigen::VectorXd nle
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis...
container::aligned_vector< Motion > a_gf
Vector of joint accelerations due to the gravity field.
container::aligned_vector< Eigen::Vector3d > com
Vector of subtree center of mass positions expressed in the root joint of the subtree. In other words, com[j] is the CoM position of the subtree supported by joint and expressed in the joint frame . The element com[0] corresponds to the center of mass position of the whole model and expressed in the global frame.
JointDataVector joints
Vector of se3::JointData associated to the se3::JointModel stored in model, encapsulated in JointData...
Motion gravity
Spatial gravity of the model.
Eigen::MatrixXd M
The joint space inertia matrix (a square matrix of dim model.nv).
container::aligned_vector< SE3 > liMi
Vector of relative joint placements (wrt the body parent).
container::aligned_vector< SE3 > oMi
Vector of absolute joint placements (wrt the world).
bool check(const AlgorithmCheckerBase< D > &checker=AlgorithmCheckerBase< D >()) const
container::aligned_vector< Inertia > inertias
Spatial inertias of the body i expressed in the supporting joint frame i.
container::aligned_vector< Force > f
Vector of body forces expressed in the local frame of the joint. For each body, the force represents ...
container::aligned_vector< Motion > v
Vector of joint velocities expressed at the centers of the joints.
int njoints
Number of joints.
std::vector< double > mass
Vector of subtree mass. In other words, mass[j] is the mass of the subtree supported by joint ...