This tutorial introduces the collision checking interface.
Amino provides an interface to the Flexible Collision Library
Collision Detection
The collision detection interface checks whether there are any collisions between geometry (meshes, primitive shapes) at a given configuration. Optionally, it can output a set of all colliding frame pairs.
Robot models often contain geometry that is always in collision, either due to physical robot parts that are in contact by design or due to approximations of the true geometry. We ignore such contacts during collision detection by specifying allowable collisions as a set of frame pairs. The collision detection interface will all collisions between frames in the allowed collisions set.
Example Code
from math import pi, sin
from time import sleep
import os
from amino import SceneWin, SceneGraph, SceneFK, SceneCollisionSet, SceneCollision
scene_plugin = ("{}/../plugin/7dof/libscene.so".format(os.path.dirname(__file__)))
scene_name = "7dof"
sg = SceneGraph()
sg.load(scene_plugin, scene_name)
sg.init()
win = SceneWin(scenegraph=sg, start=True, background=True)
fk = SceneFK(sg)
config_dict = {
"s1": -.75 * pi,
"e": .75 * pi,
"f0": .125 * pi,
"f1": .125 * pi,
"f2": .125 * pi
}
cl = SceneCollision(sg)
cl_set = SceneCollisionSet(sg)
cl.allow_config(config_dict)
dt = 1.0 / 60
t = 0
while win.is_runnining():
f = (30 + 30 * sin(t)) * (pi / 180)
config_dict['f0'] = f
config_dict['f1'] = f
config_dict['f2'] = f
win.config = config_dict
fk.config = config_dict
is_collision = cl.check(fk, cl_set)
print("Collision: %s" % ('yes' if is_collision else 'no'))
for i in range(0, sg.frame_count):
for j in range(0, i):
if cl_set[i, j]:
print(" %s, %s" % (sg.ensure_frame_name(i),
sg.ensure_frame_name(j)))
sleep(dt)
t += dt
Signed Distance
TODO
See Also
Python
C
References