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:
objectMain class for artificial potential field computations including attractive and repulsive potential calculations with configurable gain parameters.
Constructor
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)
βurchinβ: Legacy urchin parser (requires urchin, not NumPy 2.0 compatible)
β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 urchin.urdf.URDF.load()
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 visual mesh in the robotβs links.
- 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]ο
Transform convex hull vertices by a 4x4 transformation matrix.
- Parameters:
convex_hull β ConvexHull object
transform β 4x4 transformation matrix
- Returns:
Transformed convex hull
- Return type:
ConvexHull
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 β 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 urchin 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ο
urchin β URDF processing library
scipy.spatial β Convex hull computations
NumPy β Numerical array operations