1 #include "pinocchio/parsers/urdf.hpp" 3 #include "pinocchio/algorithm/joint-configuration.hpp" 4 #include "pinocchio/algorithm/kinematics-derivatives.hpp" 9 #ifndef PINOCCHIO_MODEL_DIR 10 #define PINOCCHIO_MODEL_DIR "path_to_the_model_dir" 12 int main(
int argc,
char ** argv)
36 Data::Matrix6x v_partial_dq(6,model.
nv), a_partial_dq(6,model.
nv), a_partial_dv(6,model.
nv), a_partial_da(6,model.
nv);
37 v_partial_dq.setZero();
38 a_partial_dq.setZero(); a_partial_dv.setZero(); a_partial_da.setZero();
40 a_partial_dq,a_partial_dv,a_partial_da);
46 a_partial_dq,a_partial_dv,a_partial_da);
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
The WORLD frame convention corresponds to the frame concident with the Universe/Inertial frame but mo...
int njoints
Number of joints.
void randomConfiguration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &lowerLimits, const Eigen::MatrixBase< ConfigVectorIn2 > &upperLimits, const Eigen::MatrixBase< ReturnType > &qout)
Generate a configuration vector uniformly sampled among provided limits.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
The LOCAL frame convention corresponds to the frame directly attached to the moving part (Joint...
void computeForwardKinematicsDerivatives(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)
Computes all the terms required to compute the derivatives of the placement, spatial velocity and acc...
int main(int argc, char **argv)
void getJointAccelerationDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &a_partial_dq, const Eigen::MatrixBase< Matrix6xOut3 > &a_partial_dv, const Eigen::MatrixBase< Matrix6xOut4 > &a_partial_da)
Computes the partial derivaties of the spatial acceleration of a given with respect to the joint conf...
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
Main pinocchio namespace.
int nv
Dimension of the velocity vector space.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
JointCollectionTpl & model
#define PINOCCHIO_MODEL_DIR