Potential Field API Reference#
This page documents ManipulaPy.potential_field, the module for potential field path planning with attractive and repulsive potential computations, gradient calculations, and collision checking for robotic manipulator motion planning.
Tip
For conceptual explanations, see Potential Field Module User Guide.
—
PotentialField Class#
- class ManipulaPy.potential_field.PotentialField(attractive_gain=1.0, repulsive_gain=100.0, influence_distance=0.5)[source]#
Bases:
objectArtificial potential field for attractive and repulsive joint-space costs.
Main class for artificial potential field computations including attractive and repulsive potential calculations with configurable gain parameters.
Constructor
- __init__(attractive_gain=1.0, repulsive_gain=100.0, influence_distance=0.5)[source]#
Initialize potential gains and obstacle influence distance.
Parameters:
attractive_gain (float, optional) – Gain coefficient for attractive potential (default: 1.0)
repulsive_gain (float, optional) – Gain coefficient for repulsive potential (default: 100.0)
influence_distance (float, optional) – Maximum distance for repulsive influence (default: 0.5)
—
Potential Field Computations#
Attractive Potential#
- PotentialField.compute_attractive_potential(q, q_goal)[source]#
Compute the attractive potential.
Computes quadratic attractive potential energy toward goal configuration.
Parameters:
q (numpy.ndarray) – Current configuration vector
q_goal (numpy.ndarray) – Goal configuration vector
Returns:
float – Attractive potential energy
Mathematical Implementation:
\[U_{att}(q) = \frac{1}{2} \xi \|q - q_{goal}\|^2\]Where ξ is the attractive_gain parameter.
Repulsive Potential#
- PotentialField.compute_repulsive_potential(q, obstacles)[source]#
Compute the repulsive potential.
Computes repulsive potential energy from obstacle configurations. Uses inverse distance squared repulsion with influence distance cutoff.
Parameters:
q (numpy.ndarray) – Current configuration vector
obstacles (list) – List of obstacle configuration vectors
Returns:
float – Total repulsive potential energy
Mathematical Implementation:
\[U_{rep}(q) = 10 \sum_{i} 2\eta \left(\frac{1}{\rho_i} - \frac{1}{\rho_0}\right)^2\]Where: - η is the repulsive_gain parameter - ρᵢ is the distance to obstacle i - ρ₀ is the influence_distance parameter - Scaling factor of 10 applied to final result
Gradient Computation#
- PotentialField.compute_gradient(q, q_goal, obstacles)[source]#
Compute the gradient of the potential field.
Computes the total gradient vector of the potential field for navigation. Combines attractive and repulsive gradient components.
Parameters:
q (numpy.ndarray) – Current configuration vector
q_goal (numpy.ndarray) – Goal configuration vector
obstacles (list) – List of obstacle configuration vectors
Returns:
numpy.ndarray – Total gradient vector
Implementation Details:
Attractive Gradient:
\[\nabla U_{att}(q) = \xi (q - q_{goal})\]Repulsive Gradient:
\[\nabla U_{rep}(q) = \sum_{i} 5\eta \left(\frac{1}{\rho_i} - \frac{1}{\rho_0}\right) \frac{1}{\rho_i^3} (q - q_{obs,i})\]Total Gradient:
\[\nabla U_{total}(q) = \nabla U_{att}(q) + \nabla U_{rep}(q)\]
—
CollisionChecker Class#
- class ManipulaPy.potential_field.CollisionChecker(urdf_path, backend='builtin', load_meshes=True)[source]#
Bases:
objectCollision checker using URDF visual/collision geometry and convex hulls.
- Supports multiple URDF parser backends:
“builtin”: Native ManipulaPy parser (NumPy 2.0 compatible, default)
“pybullet”: PyBullet-based parser (requires pybullet)
URDF-based collision detection system using convex hull approximations for robotic manipulator self-collision and environment collision checking.
Constructor
- __init__(urdf_path, backend='builtin', load_meshes=True)[source]#
Initializes a CollisionChecker object.
Parameters:
urdf_path (str) – File path to robot URDF description
Initialization Process:
Loads URDF using ManipulaPy’s native URDF parser
Extracts visual geometry from robot links
Generates convex hulls for collision approximation
Stores hull dictionary indexed by link names
—
Collision Detection Methods#
Hull Generation#
- CollisionChecker._create_convex_hulls()[source]#
Creates a dictionary of convex hulls for each link, preferring collision geometry and falling back to visual geometry with a one-shot warning.
- Returns:
- A dictionary where the keys are the names of the robot links
and the values are the corresponding convex hulls.
- Return type:
Generates convex hull approximations from URDF visual mesh data.
Returns:
dict – Dictionary mapping link names to ConvexHull objects
Processing Pipeline:
Iterates through robot.links
Extracts visual geometry meshes
Validates mesh.vertices attribute existence
Constructs scipy.spatial.ConvexHull from vertices
Associates hulls with link names
Geometric Transformation#
- CollisionChecker._transform_convex_hull(convex_hull, transform)[source]#
Apply a 4x4 transform to a ConvexHull and return a NEW ConvexHull.
Retained for backwards compatibility with existing tests (test_potential_field_coverage.py, test_potential_field_extended.py) that call this method directly. Internal callers in check_collision transform cached vertices directly via matrix multiply and skip the ConvexHull rebuild — prefer that path for new code.
Transforms convex hull points using homogeneous transformation matrices.
Parameters:
convex_hull (ConvexHull) – Original convex hull object
transform (numpy.ndarray) – 4×4 homogeneous transformation matrix
Returns:
ConvexHull – Transformed convex hull object
Mathematical Implementation:
\[P_{transformed} = R \cdot P_{original}^T + t\]Where: - R is the 3×3 rotation matrix (transform[:3, :3]) - t is the 3×1 translation vector (transform[:3, 3]) - P represents point coordinates
Collision Detection#
- CollisionChecker.check_collision(thetalist)[source]#
Check for self-collision at a given joint configuration.
- Parameters:
thetalist (Any) – Joint configuration (array or dict)
- Returns:
True if collision detected, False otherwise
- Return type:
Performs comprehensive self-collision detection for given joint configuration.
Parameters:
thetalist (numpy.ndarray) – Joint angle configuration vector
Returns:
bool – True if collision detected, False otherwise
Detection Algorithm:
Forward Kinematics: Compute link transforms using robot.link_fk(cfg=thetalist)
Hull Transformation: Transform each link’s convex hull to world coordinates
Pairwise Intersection: Check all link pairs for hull intersections
Self-Exclusion: Skip collision checks between identical links
Boolean Result: Return True on first intersection found
—
Data Structures and Internal Representation#
Convex Hull Storage#
Internal convex_hulls dictionary structure:
convex_hulls = {
"link_name_1": ConvexHull(vertices_1),
"link_name_2": ConvexHull(vertices_2),
# ... additional links
}
ConvexHull Properties#
Each ConvexHull object contains:
points: Original vertex coordinates
vertices: Indices of vertices forming the hull
simplices: Triangular faces of the hull
equations: Hyperplane equations for faces
Forward Kinematics Integration#
Integration with ManipulaPy URDF processing:
Input: Joint configuration (thetalist)
Method: robot.link_fk(cfg=thetalist)
Output: Dictionary {link_name: 4×4_transform_matrix}
—
Computational Complexity Analysis#
Potential Field Methods#
Method |
Complexity |
Dominant Operations |
|---|---|---|
|
O(n) |
Vector subtraction + norm |
|
O(k×n) |
k obstacles × distance computation |
|
O(k×n) |
k obstacles × gradient calculation |
Collision Detection Methods#
Method |
Complexity |
Dominant Operations |
|---|---|---|
|
O(m×v³) |
m links × ConvexHull(v vertices) |
|
O(v) |
v vertices × matrix multiplication |
|
O(L²×v) |
L² link pairs × hull intersection |
Where: - n: Configuration space dimensions - k: Number of obstacles - m: Number of robot links - v: Average vertices per mesh - L: Number of links with visual geometry
—
Numerical Implementation Details#
Potential Field Scaling#
Applied scaling factors in implementation:
Repulsive potential: 10× multiplier on final result
Repulsive gradient: 5× multiplier on gradient magnitude
Distance threshold: influence_distance parameter cutoff
Distance Computations#
All distance calculations use numpy.linalg.norm():
Method: Euclidean L2 norm
Input: Configuration space vectors
Precision: Double precision floating point
Matrix Operations#
Convex hull transformations use optimized NumPy operations:
Rotation: 3×3 matrix multiplication with broadcasted points
Translation: Vector addition with reshaped translation vector
Memory layout: Contiguous arrays for efficient computation
Intersection Detection#
Hull intersection testing relies on scipy.spatial.ConvexHull:
Algorithm: Built-in intersection testing methods
Precision: Computational geometry tolerance handling
Robustness: Handles degenerate cases automatically
—
Error Handling and Edge Cases#
URDF Processing Errors#
Missing files: URDF.load() exception handling
Invalid geometry: hasattr() validation for mesh.vertices
Empty meshes: Automatic skipping of links without valid geometry
Convex Hull Failures#
Coplanar points: scipy.spatial.ConvexHull internal handling
Insufficient vertices: Minimum 4 points required for 3D hulls
Numerical precision: Tolerance-based geometric computations
Potential Field Singularities#
Zero distance: Protected by influence_distance > 0 requirement
Infinite gradients: Prevented by distance threshold checking
Numerical overflow: Managed through finite gain parameters
—
Memory Management#
Convex Hull Storage#
Memory allocation for collision checking:
Hull objects: Persistent storage throughout object lifetime
Transformed hulls: Temporary allocation during collision checks
Point arrays: Copy operations for transformation safety
Potential Field Computations#
Memory usage characteristics:
Gradient arrays: Allocated once, reused for multiple obstacles
Distance scalars: Temporary variables with automatic cleanup
Configuration vectors: Input parameter references (no copying)
—
See Also#
Path Planning API Reference – Trajectory planning integration with potential fields
Kinematics API Reference – Forward kinematics for collision checking
Utils Module – Mathematical utilities for vector operations
URDF Processor API Reference – URDF loading and processing capabilities
External Dependencies#
scipy.spatial – Convex hull computations
NumPy – Numerical array operations