Skip to content

Commit 1e7778f

Browse files
committed
removed extraneous include
1 parent 8b91b68 commit 1e7778f

File tree

1 file changed

+1
-2
lines changed

1 file changed

+1
-2
lines changed

src/prpy/base/mico.py

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,6 @@
3333
from std_msgs.msg import Float64
3434
import rospy
3535
from ..util import Watchdog
36-
from functools import partial
3736

3837
class Mico(Manipulator):
3938
def __init__(self, sim,
@@ -77,7 +76,7 @@ def __init__(self, sim,
7776
self.velocity_publishers = [rospy.Publisher(topic_name, Float64, queue_size=1) for topic_name in self.velocity_topic_names]
7877

7978
#create watchdog to send zero velocity
80-
self.servo_watchdog = Watchdog(timeout_duration=0.3, handler=lambda: self.SendVelocitiesToMico([0.,0.,0.,0.,0.,0.,]))
79+
self.servo_watchdog = Watchdog(timeout_duration=0.25, handler=lambda: self.SendVelocitiesToMico([0.,0.,0.,0.,0.,0.,]))
8180

8281
def CloneBindings(self, parent):
8382
super(Mico, self).CloneBindings(parent)

0 commit comments

Comments
 (0)