BB.Collision (bb v0.15.3)

Copy Markdown View Source

Collision detection for BB robots.

This module provides self-collision detection and environment collision detection, following the same architectural pattern as BB.Robot.Kinematics.

Self-Collision Detection

Self-collision checking determines if any parts of the robot are colliding with each other. Adjacent links (connected by a joint) are automatically excluded from collision checks since they are expected to be in contact.

# Quick boolean check
BB.Collision.self_collision?(robot, positions)

# Detailed collision information
BB.Collision.detect_self_collisions(robot, positions)

Environment Collision Detection

Environment collision checks if the robot collides with obstacles in the workspace.

obstacles = [
  BB.Collision.obstacle(:box, centre, half_extents),
  BB.Collision.obstacle(:sphere, centre, radius)
]

BB.Collision.collides_with?(robot, positions, obstacles)

Performance

Collision detection uses a two-phase approach:

  1. Broad phase: Fast AABB overlap tests to eliminate non-colliding pairs
  2. Narrow phase: Precise primitive intersection tests for potential collisions

For a typical 6-DOF robot, self-collision checks complete in under 1ms.

Summary

Functions

Build a set of adjacent link pairs from the robot topology.

Check if the robot collides with any obstacles at the given joint positions.

Detect all collisions between the robot and environment obstacles.

Detect all self-collisions at the given joint positions.

Create an obstacle for environment collision detection.

Check if the robot is in self-collision at the given joint positions.

Types

collision_info()

@type collision_info() :: %{
  link_a: atom(),
  link_b: atom() | :environment,
  collision_a: atom() | nil,
  collision_b: atom() | nil,
  penetration_depth: float()
}

obstacle()

@type obstacle() :: %{
  type: :sphere | :capsule | :box,
  geometry: BB.Collision.Primitives.geometry(),
  aabb: BB.Collision.BroadPhase.aabb()
}

positions()

@type positions() :: %{required(atom()) => float()}

Functions

build_adjacency_set(robot)

@spec build_adjacency_set(BB.Robot.t()) :: MapSet.t({atom(), atom()})

Build a set of adjacent link pairs from the robot topology.

Adjacent links are connected by a joint and should not be checked for collision.

collides_with?(robot, positions, obstacles, opts \\ [])

@spec collides_with?(BB.Robot.t(), positions(), [obstacle()], keyword()) :: boolean()

Check if the robot collides with any obstacles at the given joint positions.

Options

  • :margin - Safety margin in metres (default: 0.0)

Examples

obstacles = [BB.Collision.obstacle(:sphere, Vec3.new(0.5, 0, 0.3), 0.1)]
BB.Collision.collides_with?(robot, positions, obstacles)

detect_collisions(robot, positions, obstacles, opts \\ [])

@spec detect_collisions(BB.Robot.t(), positions(), [obstacle()], keyword()) :: [
  collision_info()
]

Detect all collisions between the robot and environment obstacles.

Options

  • :margin - Safety margin in metres (default: 0.0)

detect_self_collisions(robot, positions, opts \\ [])

@spec detect_self_collisions(BB.Robot.t(), positions(), keyword()) :: [
  collision_info()
]

Detect all self-collisions at the given joint positions.

Returns a list of collision info maps describing each collision. Adjacent links (connected by a joint) are excluded from checks.

Options

  • :margin - Safety margin in metres added to all geometries (default: 0.0)

Examples

collisions = BB.Collision.detect_self_collisions(robot, positions)
# => [%{link_a: :forearm, link_b: :base, collision_a: nil, collision_b: nil, penetration_depth: 0.02}]

obstacle(atom, centre, radius)

@spec obstacle(:sphere, BB.Math.Vec3.t(), float()) :: obstacle()
@spec obstacle(:box, BB.Math.Vec3.t(), BB.Math.Vec3.t()) :: obstacle()

Create an obstacle for environment collision detection.

Sphere

obstacle = BB.Collision.obstacle(:sphere, centre, radius)

Capsule

obstacle = BB.Collision.obstacle(:capsule, point_a, point_b, radius)

Axis-Aligned Box

obstacle = BB.Collision.obstacle(:box, centre, half_extents)

Oriented Box

rotation = Quaternion.from_axis_angle(Vec3.unit_z(), :math.pi() / 4)
obstacle = BB.Collision.obstacle(:box, centre, half_extents, rotation)

obstacle(atom, point_a, point_b, radius)

@spec obstacle(:capsule, BB.Math.Vec3.t(), BB.Math.Vec3.t(), float()) :: obstacle()
@spec obstacle(:box, BB.Math.Vec3.t(), BB.Math.Vec3.t(), BB.Math.Quaternion.t()) ::
  obstacle()

self_collision?(robot, positions, opts \\ [])

@spec self_collision?(BB.Robot.t(), positions(), keyword()) :: boolean()

Check if the robot is in self-collision at the given joint positions.

Returns true if any non-adjacent links are colliding, false otherwise.

Options

  • :margin - Safety margin in metres added to all geometries (default: 0.0)

Examples

positions = %{shoulder: 0.0, elbow: 1.57, wrist: 0.0}
BB.Collision.self_collision?(robot, positions)
# => false

BB.Collision.self_collision?(robot, positions, margin: 0.01)
# => true  (with 1cm safety margin)