Skip to content

Commit 3c35736

Browse files
author
Michael Koval
committed
Deprecated the GetVelocityLimits override on WAM.
1 parent 620a56a commit 3c35736

File tree

1 file changed

+8
-31
lines changed

1 file changed

+8
-31
lines changed

src/prpy/base/wam.py

Lines changed: 8 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030

3131
import numpy
3232
import openravepy
33+
import warnings
3334
from manipulator import Manipulator
3435
from prpy.clone import Clone
3536
from .. import util
@@ -161,7 +162,7 @@ def ServoTo(manipulator, target, duration, timeStep=0.05, collisionChecking=True
161162
else:
162163
return False
163164

164-
def GetVelocityLimits(self, openrave=True, owd=True):
165+
def GetVelocityLimits(self, openrave=None, owd=None):
165166
"""Get the OpenRAVE and OWD joint velocity limits.
166167
This function checks both the OpenRAVE and OWD joint velocity limits.
167168
If they do not match, a warning is printed and the minimum value is
@@ -170,37 +171,13 @@ def GetVelocityLimits(self, openrave=True, owd=True):
170171
@param owd flag to set the OWD velocity limits
171172
@return list of velocity limits, in radians per second
172173
"""
173-
# Update the OpenRAVE limits.
174-
if openrave:
175-
or_velocity_limits = Manipulator.GetVelocityLimits(self)
176-
if self.simulated or not owd:
177-
return or_velocity_limits
178-
179-
# Update the OWD limits.
180-
if owd and not self.simulated:
181-
args = [ 'GetSpeed' ]
182-
args_str = ' '.join(args)
183-
owd_speed_limits_all = self.controller.SendCommand(args_str)
184-
#if we get nothing back, e.g. if the arm isn't running, return openrave lims
185-
if owd_speed_limits_all is None:
186-
return or_velocity_limits
187-
188-
owd_speed_limits = map(float, owd_speed_limits_all.split(','));
189-
#first 7 numbers are velocity limits
190-
owd_velocity_limits = numpy.array(owd_speed_limits[0:len(self.GetIndices())])
191-
192-
diff_arr = numpy.subtract(or_velocity_limits, owd_velocity_limits)
193-
max_diff = max(abs(diff_arr))
194-
195-
if max_diff > 0.01:
196-
# TODO: Change this to use the logging framework.
197-
print('GetVelocityLimits Error: openrave and owd limits very different')
198-
print('\tOpenrave limits:\t' + str(or_velocity_limits))
199-
print('\tOWD limits:\t\t' + str(owd_velocity_limits))
200-
201-
return numpy.minimum(or_velocity_limits, owd_velocity_limits)
174+
if openrave is not None or owd is not None:
175+
warnings.warn(
176+
'The "openrave" and "owd" flags are deprecated in'
177+
' GetVelocityLimits and will be removed in a future version.',
178+
DeprecationWarning)
202179

203-
return or_velocity_limits
180+
return Manipulator.GetVelocityLimits(self)
204181

205182
def SetVelocityLimits(self, velocity_limits, min_accel_time,
206183
openrave=True, owd=True):

0 commit comments

Comments
 (0)