pinocchio  2.6.17
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
Collision detection and distances

Python

from __future__ import print_function
import pinocchio as pin, hppfcl
import os
from os.path import dirname, join, abspath
pinocchio_model_dir = join(dirname(dirname(str(abspath(__file__)))),"models")
model_path = join(pinocchio_model_dir,"example-robot-data/robots")
mesh_dir = pinocchio_model_dir
urdf_filename = "romeo_small.urdf"
urdf_model_path = join(join(model_path,"romeo_description/urdf"),urdf_filename)
# Load model
model = pin.buildModelFromUrdf(urdf_model_path,pin.JointModelFreeFlyer())
# Load collision geometries
geom_model = pin.buildGeomFromUrdf(model,urdf_model_path,mesh_dir,pin.GeometryType.COLLISION)
# Add collisition pairs
geom_model.addAllCollisionPairs()
print("num collision pairs - initial:",len(geom_model.collisionPairs))
# Remove collision pairs listed in the SRDF file
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))
# Load reference configuration
pin.loadReferenceConfigurations(model,srdf_model_path)
# Retrieve the half sitting position from the SRDF file
q = model.referenceConfigurations["half_sitting"]
# Create data structures
data = model.createData()
geom_data = pin.GeometryData(geom_model)
# Compute all the collisions
pin.computeCollisions(model,data,geom_model,geom_data,q,False)
# Print the status of collision for all collision pairs
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")
# Compute for a single pair of collision
pin.updateGeometryPlacements(model,data,geom_model,geom_data,q)
pin.computeCollision(geom_model,geom_data,0)

C++

#include "pinocchio/parsers/urdf.hpp"
#include "pinocchio/parsers/srdf.hpp"
#include "pinocchio/algorithm/joint-configuration.hpp"
#include "pinocchio/algorithm/geometry.hpp"
#include <iostream>
// PINOCCHIO_MODEL_DIR is defined by the CMake but you can define your own modeldirectory here.
#ifndef PINOCCHIO_MODEL_DIR
#define PINOCCHIO_MODEL_DIR "path_to_the_model_dir"
#endif
int main(int /*argc*/, char ** /*argv*/)
{
using namespace pinocchio;
const std::string robots_model_path = PINOCCHIO_MODEL_DIR;
// You should change here to set up your own URDF file
const std::string urdf_filename = robots_model_path + std::string("/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
// You should change here to set up your own SRDF file
const std::string srdf_filename = robots_model_path + std::string("/example-robot-data/robots/talos_data/srdf/talos.srdf");
// Load the URDF model contained in urdf_filename
Model model;
pinocchio::urdf::buildModel(urdf_filename,model);
// Build the data associated to the model
Data data(model);
// Load the geometries associated to model which are contained in the URDF file
GeometryModel geom_model;
pinocchio::urdf::buildGeom(model, urdf_filename, pinocchio::COLLISION, geom_model, robots_model_path);
// Add all possible collision pairs and remove the ones collected in the SRDF file
geom_model.addAllCollisionPairs();
pinocchio::srdf::removeCollisionPairs(model, geom_model, srdf_filename);
// Build the data associated to the geom_model
GeometryData geom_data(geom_model); // contained the intermediate computations, like the placement of all the geometries with respect to the world frame
// Load the reference configuration of the robots (this one should be collision free)
pinocchio::srdf::loadReferenceConfigurations(model,srdf_filename); // the reference configuratio stored in the SRDF file is called half_sitting
const Model::ConfigVectorType & q = model.referenceConfigurations["half_sitting"];
// And test all the collision pairs
computeCollisions(model,data,geom_model,geom_data,q);
// Print the status of all the collision pairs
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;
}
// If you want to stop as soon as a collision is encounter, just add false for the final default argument stopAtFirstCollision
computeCollisions(model,data,geom_model,geom_data,q,true);
// And if you to check only one collision pair, e.g. the third one, at the neutral element of the Configuration Space of the robot
const PairIndex pair_id = 2;
const Model::ConfigVectorType q_neutral = neutral(model);
updateGeometryPlacements(model, data, geom_model, geom_data, q_neutral); // performs a forward kinematics over the whole kinematics model + update the placement of all the geometries contained inside geom_model
computeCollision(geom_model, geom_data, pair_id);
return 0;
}
pinocchio::DataTpl
Definition: data.hpp:29
pinocchio::updateGeometryPlacements
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.
pinocchio::ModelTpl::ConfigVectorType
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
Definition: model.hpp:66
pinocchio::GeometryData
Definition: geometry.hpp:187
pinocchio::CollisionPair
Definition: fcl.hpp:74
pinocchio::GeometryModel::addAllCollisionPairs
void addAllCollisionPairs()
Add all possible collision pairs.
pinocchio::urdf::buildModel
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...
pinocchio::GeometryModel::collisionPairs
CollisionPairVector collisionPairs
Vector of collision pairs.
Definition: geometry.hpp:183
pinocchio::urdf::buildGeom
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 ...
pinocchio::srdf::loadReferenceConfigurations
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...
pinocchio::computeCollisions
bool computeCollisions(const GeometryModel &geom_model, GeometryData &geom_data, const bool stopAtFirstCollision=false)
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeome...
pinocchio::GeometryModel
Definition: geometry.hpp:22
pinocchio::neutral
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
Return the neutral configuration element related to the model configuration space.
Definition: joint-configuration.hpp:257
pinocchio::ModelTpl
Definition: fwd.hpp:23
pinocchio::computeCollision
bool computeCollision(const GeometryModel &geom_model, GeometryData &geom_data, const PairIndex pair_id)
Compute the collision status between a SINGLE collision pair. The result is store in the collisionRes...
pinocchio
Main pinocchio namespace.
Definition: treeview.dox:11
pinocchio::srdf::removeCollisionPairs
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...