Skip to content

Commit

Permalink
Throw a more meaningful error when TOPPRA fails
Browse files Browse the repository at this point in the history
  • Loading branch information
m-decoster committed Apr 25, 2024
1 parent e146b1a commit 0f418bc
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 1 deletion.
2 changes: 2 additions & 0 deletions airo_drake/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
filter_collisions_between_all_body_pairs,
list_collisions_between_bodies,
)
from airo_drake.exceptions import TimeParameterizationError


__all__ = [
Expand Down Expand Up @@ -75,4 +76,5 @@
"calculate_valid_joint_paths",
"filter_collisions_between_all_body_pairs",
"list_collisions_between_bodies",
"TimeParameterizationError",
]
2 changes: 2 additions & 0 deletions airo_drake/exceptions.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
class TimeParameterizationError(RuntimeError):
"""Raised when a path could not be time parameterized."""
4 changes: 3 additions & 1 deletion airo_drake/time_parametrization/toppra.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
from pydrake.multibody.plant import MultibodyPlant
from pydrake.trajectories import PathParameterizedTrajectory, PiecewisePolynomial, Trajectory

from airo_drake.exceptions import TimeParameterizationError


def time_parametrize_toppra(
plant: MultibodyPlant,
Expand Down Expand Up @@ -41,7 +43,7 @@ def time_parametrize_toppra(
time_parametrization = toppra.SolvePathParameterization()

if time_parametrization is None:
raise ValueError("TOPP-RA failed to find a valid time parametrization.")
raise TimeParameterizationError("TOPP-RA failed to find a valid time parametrization.")

joint_trajectory = PathParameterizedTrajectory(joint_trajectory, time_parametrization)

Expand Down

0 comments on commit 0f418bc

Please sign in to comment.