amino  1.0-beta2
Lightweight Robot Utility Library
Collision

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

#!/usr/bin/env python3
# File: t5.1-collision-check.py
# =======================
#
# Collision Checking
from math import pi, sin
from time import sleep
import os
from amino import SceneWin, SceneGraph, SceneFK, SceneCollisionSet, SceneCollision
# Scene Parameters
scene_plugin = ("{}/../plugin/7dof/libscene.so".format(os.path.dirname(__file__)))
scene_name = "7dof"
# Create an (empty) scene graph
sg = SceneGraph()
# Load the scene plugin
sg.load(scene_plugin, scene_name)
# Initialize the scene graph
sg.init()
# Create a window, pass the scenegraph, and start
win = SceneWin(scenegraph=sg, start=True, background=True)
# Create the FK context
fk = SceneFK(sg)
# Initial Configuration
config_dict = {
"s1": -.75 * pi,
"e": .75 * pi,
"f0": .125 * pi,
"f1": .125 * pi,
"f2": .125 * pi
}
# Collision context and collision set
cl = SceneCollision(sg)
cl_set = SceneCollisionSet(sg)
# Allowable collisions
cl.allow_config(config_dict)
dt = 1.0 / 60
t = 0
while win.is_runnining():
# wiggle fingers
f = (30 + 30 * sin(t)) * (pi / 180)
config_dict['f0'] = f
config_dict['f1'] = f
config_dict['f2'] = f
# update window
win.config = config_dict
# update forward kinematics
fk.config = config_dict
# check collision
is_collision = cl.check(fk, cl_set)
# print collision results
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 till next cycle
sleep(dt)
t += dt

Signed Distance

TODO

See Also

Python

C

References