Go to the documentation of this file.
11 #ifndef PINOCCHIO_MODEL_DIR
12 #define PINOCCHIO_MODEL_DIR "path_to_the_model_dir"
23 + std::string(
"/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
26 robots_model_path + std::string(
"/example-robot-data/robots/talos_data/srdf/talos.srdf");
59 for (
size_t k = 0; k <
geom_model.collisionPairs.size(); ++k)
64 std::cout <<
"collision pair: " <<
cp.first <<
" , " <<
cp.second <<
" - collision: ";
65 std::cout << (
cr.isCollision() ?
"yes" :
"no") << std::endl;
bool computeCollisions(BroadPhaseManagerBase< BroadPhaseManagerDerived > &broadphase_manager, CollisionCallBackBase *callback)
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeome...
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.
bool computeCollision(const GeometryModel &geom_model, GeometryData &geom_data, const PairIndex pair_id, fcl::CollisionRequest &collision_request)
Compute the collision status between a SINGLE collision pair. The result is store in the collisionRes...
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, 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 ...
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
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 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.
#define PINOCCHIO_MODEL_DIR
JointCollectionTpl & model
Main pinocchio namespace.
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...
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:42