from pathlib import Path
import pinocchio as pin
pinocchio_model_dir = Path(__file__).parent.parent / "models"
model_path = pinocchio_model_dir / "example-robot-data/robots"
mesh_dir = pinocchio_model_dir
urdf_filename = "romeo_small.urdf"
urdf_model_path = model_path / "romeo_description/urdf" / urdf_filename
model = pin.buildModelFromUrdf(urdf_model_path, pin.JointModelFreeFlyer())
geom_model = pin.buildGeomFromUrdf(
model, urdf_model_path, pin.GeometryType.COLLISION, mesh_dir
)
geom_model.addAllCollisionPairs()
print("num collision pairs - initial:", len(geom_model.collisionPairs))
srdf_filename = "romeo.srdf"
srdf_model_path = model_path / "romeo_description/srdf" / srdf_filename
pin.removeCollisionPairs(model, geom_model, srdf_model_path)
print(
"num collision pairs - after removing useless collision pairs:",
len(geom_model.collisionPairs),
)
pin.loadReferenceConfigurations(model, srdf_model_path)
q = model.referenceConfigurations["half_sitting"]
data = model.createData()
geom_data = pin.GeometryData(geom_model)
pin.computeCollisions(model, data, geom_model, geom_data, q, False)
for k in range(len(geom_model.collisionPairs)):
cr = geom_data.collisionResults[k]
cp = geom_model.collisionPairs[k]
print(
"collision pair:",
cp.first,
",",
cp.second,
"- collision:",
"Yes" if cr.isCollision() else "No",
)
pin.updateGeometryPlacements(model, data, geom_model, geom_data, q)
pin.computeCollision(geom_model, geom_data, 0)
#include "pinocchio/parsers/urdf.hpp"
#include "pinocchio/parsers/srdf.hpp"
#include "pinocchio/algorithm/joint-configuration.hpp"
#include "pinocchio/algorithm/geometry.hpp"
#include "pinocchio/collision/collision.hpp"
#include <iostream>
#ifndef PINOCCHIO_MODEL_DIR
#define PINOCCHIO_MODEL_DIR "path_to_the_model_dir"
#endif
int main(int , char ** )
{
const std::string robots_model_path = PINOCCHIO_MODEL_DIR;
const std::string urdf_filename =
robots_model_path
+ std::string("/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
const std::string srdf_filename =
robots_model_path + std::string("/example-robot-data/robots/talos_data/srdf/talos.srdf");
Model model;
Data data(model);
GeometryModel geom_model;
model, urdf_filename, pinocchio::COLLISION, geom_model, robots_model_path);
geom_model.addAllCollisionPairs();
GeometryData geom_data(geom_model);
model,
srdf_filename);
for (size_t k = 0; k < geom_model.collisionPairs.size(); ++k)
{
const CollisionPair & cp = geom_model.collisionPairs[k];
const hpp::fcl::CollisionResult & cr = geom_data.collisionResults[k];
std::cout << "collision pair: " << cp.first << " , " << cp.second << " - collision: ";
std::cout << (cr.isCollision() ? "yes" : "no") << std::endl;
}
const PairIndex pair_id = 2;
model, data, geom_model, geom_data,
q_neutral);
return 0;
}
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...
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 ...
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, const bool mimic=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.
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...
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.
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
Return the neutral configuration element related to the model configuration space.
bool computeCollisions(BroadPhaseManagerBase< BroadPhaseManagerDerived > &broadphase_manager, CollisionCallBackBase *callback)
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeome...
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.