stack-of-tasks / pinocchio

A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
http://stack-of-tasks.github.io/pinocchio/
BSD 2-Clause "Simplified" License
1.75k stars 372 forks source link

Supported object shapes in pinocchio #1092

Closed Linjackffy closed 4 years ago

Linjackffy commented 4 years ago

I have a question about the supported object shapes in pinocchio. In the file link.h, class Geometry has four enum type:

class Geometry
{
public:
  enum {SPHERE, BOX, CYLINDER, MESH} type;

  virtual ~Geometry(void)
  {
  }  
};

Dose this mean that other object shapes like ellipsoid、capsule and octree supported by fcl cannot created by pinocchio‘s URDF parser?

jcarpent commented 4 years ago

Dear @Linjackffy,

I think the file you are mentioning is not inside Pinocchio. In Pinocchio, to handle a geometry (Sphere, Ellipsoid, Meshes, ...), we rely on an extension of the FCL library called hpp-fcl.

To simplify its usage, we've introduced a dedicated structure called GeometryObject (see https://github.com/stack-of-tasks/pinocchio/blob/66bb1bc08669497a0da3d303841e88f68b7434bb/src/multibody/fcl.hpp#L83), which stores an FCL object.

You can then happened this GeometryObject to a GeometryModel (see https://github.com/stack-of-tasks/pinocchio/blob/66bb1bc08669497a0da3d303841e88f68b7434bb/src/multibody/geometry.hpp#L23) via the method GeometryModel::addGeometryObject.

And then use the standard computeCollisions or computeDistances of pinocchio.

jcarpent commented 4 years ago

Concerning the URDF parsers, it is able to handle all the geometries supported by the URDF parser and the convention then. We can then load meshes but the URDF does not support for instance the concept of capsules.

In Pinocchio in fact, we made the choice to replace the Cylinders by Capsules for convenience.

Linjackffy commented 4 years ago

@jcarpent Sorry for my mistake. File link.h is inside urdf_model. I would use GeometryObject to handle those object shapes. Thanks for your answer!

jmirabel commented 4 years ago

In Pinocchio in fact, we made the choice to replace the Cylinders by Capsules for convenience.

To be more precise, the URDF parser of pinocchio will convert a cylinder into a capsule only in the case below (taken from the unit test urdf.cpp):

  <link name="WAIST_LINK0">
    <collision name="test">
      <geometry>
        <cylinder radius="1" length="1"/>
      </geometry>
    </collision>
    <collision_checking>
      <!--- This tells to pinocchio to replace the cylinder called "test"
           by a capsule with the same radius and length -->
      <capsule name="test"/>
    </collision_checking>
  </link>
Linjackffy commented 4 years ago

@jmirabel thanks for your prompt!

jmirabel commented 4 years ago

Another insight: Ellipsoids are not supported by FCL. It wouldn't be hard to implement though.