1 #include "pinocchio/parsers/urdf.hpp" 2 #include "pinocchio/parsers/srdf.hpp" 4 #include "pinocchio/algorithm/joint-configuration.hpp" 5 #include "pinocchio/algorithm/geometry.hpp" 10 #ifndef PINOCCHIO_MODEL_DIR 11 #define PINOCCHIO_MODEL_DIR "path_to_the_model_dir" 20 const std::string
urdf_filename = robots_model_path + std::string(
"/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
22 const std::string
srdf_filename = robots_model_path + std::string(
"/example-robot-data/robots/talos_data/srdf/talos.srdf");
54 const hpp::fcl::CollisionResult &
cr = geom_data.collisionResults[k];
56 std::cout <<
"collision pair: " << cp.first <<
" , " << cp.second <<
" - collision: ";
57 std::cout << (cr.isCollision() ?
"yes" :
"no") << std::endl;
67 computeCollision(geom_model, geom_data, pair_id);
void loadReferenceConfigurations(ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const bool verbose=false)
Get the reference configurations of a given model associated to a SRDF file. It throws if the SRDF fi...
void removeCollisionPairs(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, GeometryModel &geom_model, const std::string &filename, const bool verbose=false)
Deactive all possible collision pairs mentioned in the SRDF file. It throws if the SRDF file is incor...
CollisionPairVector collisionPairs
Vector of collision pairs.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
#define PINOCCHIO_MODEL_DIR
ConfigVectorMap referenceConfigurations
Map of reference configurations, indexed by user given names.
bool computeCollisions(const int num_threads, const GeometryModel &geom_model, GeometryData &geom_data, const bool stopAtFirstCollision=false)
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 ...
void addAllCollisionPairs()
Add all possible collision pairs.
Main pinocchio namespace.
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
Return the neutral configuration element related to the model configuration space.
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
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.
JointCollectionTpl & model