Skip to content

Commit 5aa9150

Browse files
committed
Merge pull request #258 from personalrobotics/feature/mico_servo_pub_each_joint
Implement Servo() on MicoArm.
2 parents 9000ef6 + 2afadf7 commit 5aa9150

File tree

2 files changed

+89
-1
lines changed

2 files changed

+89
-1
lines changed

src/prpy/base/mico.py

Lines changed: 21 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,10 @@
3030

3131
import openravepy
3232
from manipulator import Manipulator
33+
from std_msgs.msg import Float64
34+
import rospy
35+
import threading
36+
from ..util import Watchdog
3337

3438
class Mico(Manipulator):
3539
def __init__(self, sim,
@@ -67,6 +71,14 @@ def __init__(self, sim,
6771
self.GetName(), '', self.GetArmIndices(), 0, True)
6872
self.servo_simulator = ServoSimulator(self, rate=20,
6973
watchdog_timeout=0.1)
74+
else:
75+
#if not simulation, create publishers for each joint
76+
self.velocity_topic_names = ['vel_j'+str(i)+'_controller/command' for i in range(1,7)]
77+
self.velocity_publishers = [rospy.Publisher(topic_name, Float64, queue_size=1) for topic_name in self.velocity_topic_names]
78+
self.velocity_publisher_lock = threading.Lock()
79+
80+
#create watchdog to send zero velocity
81+
self.servo_watchdog = Watchdog(timeout_duration=0.25, handler=self.SendVelocitiesToMico, args=[[0.,0.,0.,0.,0.,0.,]])
7082

7183
def CloneBindings(self, parent):
7284
super(Mico, self).CloneBindings(parent)
@@ -99,4 +111,12 @@ def Servo(self, velocities):
99111
self.GetRobot().GetController().Reset(0)
100112
self.servo_simulator.SetVelocity(velocities)
101113
else:
102-
raise NotImplementedError('Servo is not implemented.')
114+
self.SendVelocitiesToMico(velocities)
115+
#reset watchdog timer
116+
self.servo_watchdog.reset()
117+
118+
119+
def SendVelocitiesToMico(self, velocities):
120+
with self.velocity_publisher_lock:
121+
for velocity_publisher,velocity in zip(self.velocity_publishers, velocities):
122+
velocity_publisher.publish(velocity)

src/prpy/util.py

Lines changed: 68 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -497,6 +497,74 @@ def stop(self):
497497
def get_duration(self):
498498
return self.end - self.start
499499

500+
class Watchdog(object):
501+
'''
502+
Calls specified function after duration, unless reset/stopped beforehand
503+
504+
@param timeout_duration how long to wait before calling handler
505+
@param handler function to call after timeout_duration
506+
@param args for handler
507+
@param kwargs for handler
508+
'''
509+
def __init__(self, timeout_duration, handler, args=(), kwargs={}):
510+
self.timeout_duration = timeout_duration
511+
self.handler = handler
512+
self.handler_args = args
513+
self.handler_kwargs = kwargs
514+
515+
self.thread_checking_time = threading.Thread(target=self._check_timer_loop)
516+
self.timer_thread_lock = threading.Lock()
517+
self.start_time = time.time()
518+
self.canceled = False
519+
520+
self.thread_checking_time.start()
521+
522+
def reset(self):
523+
'''
524+
Resets the timer
525+
526+
Causes the handler function to be called after the next
527+
timeout duration is reached
528+
529+
Also restarts the timer thread if it has existed
530+
'''
531+
with self.timer_thread_lock:
532+
if self.canceled or not self.thread_checking_time.is_alive():
533+
self.thread_checking_time = threading.Thread(target=self._check_timer_loop)
534+
self.thread_checking_time.start()
535+
536+
self.start_time = time.time()
537+
self.canceled = False
538+
539+
def stop(self):
540+
'''
541+
Stop the watchdog, so it will not call handler
542+
'''
543+
with self.timer_thread_lock:
544+
self.canceled = True
545+
546+
def _check_timer_loop(self):
547+
'''
548+
Internal function for timer thread to loop
549+
550+
If elapsed time has passed, calls the handler function
551+
Exists if watchdog was canceled, or handler was called
552+
'''
553+
while True:
554+
with self.timer_thread_lock:
555+
if self.canceled:
556+
break
557+
elapsed_time = time.time() - self.start_time
558+
if elapsed_time > self.timeout_duration:
559+
self.handler(*self.handler_args, **self.handler_kwargs)
560+
with self.timer_thread_lock:
561+
self.canceled = True
562+
break
563+
else:
564+
time.sleep(self.timeout_duration - elapsed_time)
565+
566+
567+
500568

501569
def quadraticPlusJointLimitObjective(dq, J, dx, q, q_min, q_max, delta_joint_penalty=5e-1, lambda_dqdist=0.01, *args):
502570
'''

0 commit comments

Comments
 (0)