1 #include "pinocchio/multibody/fcl.hpp" 2 #include "pinocchio/parsers/urdf.hpp" 4 #include "pinocchio/algorithm/joint-configuration.hpp" 5 #include "pinocchio/algorithm/kinematics.hpp" 6 #include "pinocchio/algorithm/geometry.hpp" 11 #ifndef PINOCCHIO_MODEL_DIR 12 #define PINOCCHIO_MODEL_DIR "path_to_the_model_dir" 15 int main(
int argc,
char ** argv)
21 const std::string
urdf_filename = model_path +
"/ur_description/urdf/ur5_robot.urdf";
30 std::cout <<
"model name: " << model.
name << std::endl;
39 std::cout <<
"q: " << q.transpose() << std::endl;
49 std::cout <<
"\nJoint placements:" << std::endl;
51 std::cout << std::setw(24) << std::left
53 << std::fixed << std::setprecision(2)
54 << data.oMi[
joint_id].translation().transpose()
58 std::cout <<
"\nCollision object placements:" << std::endl;
60 std::cout << geom_id <<
": " 61 << std::fixed << std::setprecision(2)
62 << collision_data.oMg[geom_id].translation().transpose()
66 std::cout <<
"\nVisual object placements:" << std::endl;
68 std::cout << geom_id <<
": " 69 << std::fixed << std::setprecision(2)
70 << visual_data.oMg[geom_id].translation().transpose()
int njoints
Number of joints.
std::vector< std::string > names
Name of joint i
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
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Update the joint placements according to the current joint configuration.
std::string name
Model name;.
#define PINOCCHIO_MODEL_DIR
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...
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geom_model, const std::vector< std::string > &package_paths=std::vector< std::string >(),::hpp::fcl::MeshLoaderPtr mesh_loader=::hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user ...
Index ngeoms
The number of GeometryObjects.
Main pinocchio namespace.
int main(int argc, char **argv)
void updateGeometryPlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data, const Eigen::MatrixBase< ConfigVectorType > &q)
Apply a forward kinematics and update the placement of the geometry objects.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
JointCollectionTpl & model