-
Before I go down the wrong path, I wanted to ask here. I am trying to use Pinocchio to add "scene obstacles" to a robot model. If the obstacles are static, it's very easy to add geometry objects to the model and keep track of collisions, etc. But what to do about dynamic objects? Some options I've ran by:
One special consideration is the ability to have a single Octree in the world, but be able to update its points. I'm sure this must be a path that these tools are designed for... Is there some recommended approach to follow out of all these? Or something else I have missed in my search? Any help is much appreciated. EDIT: Playing with the Python API, I found you could just... change positions on the fly? cid = collision_model.getGeometryId("obstacle_0")
collision_model.geometryObjects[cid].placement.translation[2] += 0.05 And geometries? collision_model.geometryObjects[cid].geometry = hppfcl.Sphere(1.5) Is this valid usage? Seemed to work when I tested. |
Beta Was this translation helpful? Give feedback.
Replies: 1 comment
-
You can, of course, update the geometry placement as you want. This quantity is considered when you ask for a 0th-order forward kinematics (e.g., You can also update the geometry parameters (e.g., |
Beta Was this translation helpful? Give feedback.
You can, of course, update the geometry placement as you want. This quantity is considered when you ask for a 0th-order forward kinematics (e.g.,
updateGeometryPlacements
, that will update thegeometry_data.oMg
vector.You can also update the geometry parameters (e.g.,
collision_model.geometryObjects[cid].geometry.radius = 1.5
), but you cannot change the type. Otherwise, you need to recreate the associated data structure (that stores some functors for fast evaluation of collision checking).If you use the broadphase, when changing the dimensions of a given geometry, you will need to recompute the local AABB encompassing volume, using
collision_model.geometryObjects[cid].geometry.computeLo…