Skip to content

Commit 37cbea0

Browse files
committed
Merge pull request #196 from personalrobotics/feature/trajectorynotexecuted
Added separate exception for trajectory precondition violations.
2 parents 372db4f + bfbd7ef commit 37cbea0

File tree

2 files changed

+32
-7
lines changed

2 files changed

+32
-7
lines changed

src/prpy/base/robot.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -205,8 +205,8 @@ def PostProcessPath(self, path, defer=False, executor=None,
205205
curve through the waypoints (not implemented). If this curve is
206206
not collision free, then we fall back on...
207207
4. By default, we run a smoother that jointly times and smooths the
208-
path via self.smoother. This algorithm can change the geometric path to
209-
optimize runtime.
208+
path via self.smoother. This algorithm can change the geometric path
209+
to optimize runtime.
210210
211211
The behavior in (2) and (3) can be forced by passing constrained=True
212212
or smooth=True. By default, the case is inferred by the tag(s) attached
@@ -411,8 +411,8 @@ def do_execute():
411411
else:
412412
raise ValueError('Received unexpected value "{:s}" for defer.'.format(str(defer)))
413413

414-
415-
def ExecuteTrajectory(self, traj, defer=False, timeout=None, period=0.01, **kwargs):
414+
def ExecuteTrajectory(self, traj, defer=False, timeout=None, period=0.01,
415+
**kwargs):
416416
""" Executes a time trajectory on the robot.
417417
418418
This function directly executes a timed OpenRAVE trajectory on the
@@ -450,7 +450,7 @@ def ExecuteTrajectory(self, traj, defer=False, timeout=None, period=0.01, **kwar
450450
# Check that the current configuration of the robot matches the
451451
# initial configuration specified by the trajectory.
452452
if not util.IsAtTrajectoryStart(self, traj):
453-
raise exceptions.TrajectoryAborted(
453+
raise exceptions.TrajectoryNotExecutable(
454454
'Trajectory started from different configuration than robot.')
455455

456456
# If there was only one waypoint, at this point we are done!

src/prpy/exceptions.py

Lines changed: 27 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,26 +3,50 @@ class PrPyException(Exception):
33
Generic PrPy exception.
44
"""
55

6-
class TrajectoryAborted(PrPyException):
6+
7+
class TrajectoryException(PrPyException):
8+
"""
9+
Trajectory failed to execute.
10+
"""
11+
12+
13+
class TrajectoryNotExecutable(TrajectoryException):
14+
"""
15+
Trajectory could not begin execution.
16+
17+
This exception typically indicates that some precondition of trajectory
18+
execution was violated, such as the robot starting at a different
19+
configuration, the trajectory not being in the correct format.
20+
21+
This exception indicates that the trajectory was not even attempted due to
22+
one of these conditions.
23+
"""
24+
25+
26+
class TrajectoryAborted(TrajectoryException):
727
"""
828
Trajectory was aborted.
929
"""
1030

11-
class TrajectoryStalled(PrPyException):
31+
32+
class TrajectoryStalled(TrajectoryException):
1233
"""
1334
Trajectory stalled.
1435
"""
1536

37+
1638
class SynchronizationException(PrPyException):
1739
"""
1840
Controller synchronization failed.
1941
"""
2042

43+
2144
class SerializationException(PrPyException):
2245
"""
2346
Serialization failed.
2447
"""
2548

49+
2650
class UnsupportedTypeSerializationException(SerializationException):
2751
"""
2852
Serialization failed due to an unknown type.
@@ -35,6 +59,7 @@ def __init__(self, value):
3559
'Serializing type "{:s}.{:s}" is not supported.'.format(
3660
self.type.__module__, self.type.__name__))
3761

62+
3863
class UnsupportedTypeDeserializationException(SerializationException):
3964
"""
4065
Deserialization failed due to an unknown type.

0 commit comments

Comments
 (0)