4   servo_controller.py: classes for servo interaction 
    5   Copyright (c) 2011-2013 Vanadium Labs LLC. All right reserved. 
    7   Redistribution and use in source and binary forms, with or without 
    8   modification, are permitted provided that the following conditions are met: 
    9       * Redistributions of source code must retain the above copyright 
   10         notice, this list of conditions and the following disclaimer. 
   11       * Redistributions in binary form must reproduce the above copyright 
   12         notice, this list of conditions and the following disclaimer in the 
   13         documentation and/or other materials provided with the distribution. 
   14       * Neither the name of Vanadium Labs LLC nor the names of its  
   15         contributors may be used to endorse or promote products derived  
   16         from this software without specific prior written permission. 
   18   THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 
   19   ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 
   20   WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 
   21   DISCLAIMED. IN NO EVENT SHALL VANADIUM LABS BE LIABLE FOR ANY DIRECT, INDIRECT, 
   22   INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 
   23   LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 
   24   OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 
   25   LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE 
   26   OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF 
   27   ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 
   32 from math 
import radians
 
   34 from std_msgs.msg 
import Float64
 
   43     def __init__(self, device, name, ns="~joints"):
 
   44         Joint.__init__(self, device, name)
 
   47         self.
id = int(rospy.get_param(n+
"id"))
 
   48         self.
ticks = rospy.get_param(n+
"ticks", 1024)
 
   50         if self.
ticks == 4096:
 
   54         self.
range = rospy.get_param(n+
"range", self.
range)
 
   60         self.
max_speed = radians(rospy.get_param(n+
"max_speed",684.0)) 
 
   62         self.
invert = rospy.get_param(n+
"invert",
False)
 
   63         self.
readable = rospy.get_param(n+
"readable",
True)
 
   66         self.
level = DiagnosticStatus.OK
 
   75         self.
last = rospy.Time.now()
 
   86         rospy.Subscriber(name+
'/command', Float64, self.
commandCb)
 
   87         rospy.Service(name+
'/relax', Relax, self.
relaxCb)
 
   88         rospy.Service(name+
'/enable', Enable, self.
enableCb)
 
   89         rospy.Service(name+
'/set_speed', SetSpeed, self.
setSpeedCb)
 
   92         """ Get the new position to move to, in ticks. """ 
  120                 self.
last = rospy.Time.now()
 
  124         """ Update angle in radians by reading from servo, or by  
  125             using position passed in from a sync read (in ticks). """ 
  126         if reading > -1 
and reading < self.
ticks:     
 
  136             rospy.logdebug(
"Invalid read of servo: id " + str(self.
id) + 
", value " + str(reading))
 
  144         """ Set the position that controller is moving to.  
  145             Returns output value in ticks. """ 
  155         """ Get a diagnostics status. """ 
  156         msg = DiagnosticStatus()
 
  159             self.
status = 
"OVERHEATED, SHUTDOWN" 
  160             self.
level = DiagnosticStatus.ERROR
 
  162             self.
status = 
"OVERHEATING" 
  163             self.
level = DiagnosticStatus.WARN
 
  164         elif self.
status != 
"OVERHEATED, SHUTDOWN":
 
  166             self.
level = DiagnosticStatus.OK
 
  167         msg.level = self.
level 
  169         msg.values.append(KeyValue(
"Position", str(self.
position)))
 
  170         msg.values.append(KeyValue(
"Temperature", str(self.
temperature)))
 
  171         msg.values.append(KeyValue(
"Voltage", str(self.
voltage)))
 
  178         msg.values.append(KeyValue(
"Reads", str(self.
total_reads)))
 
  181             msg.values.append(KeyValue(
"Torque", 
"ON"))
 
  183             msg.values.append(KeyValue(
"Torque", 
"OFF"))
 
  187         """ Convert an angle to ticks, applying limits. """ 
  191         if ticks >= self.
ticks:
 
  192             return self.
ticks-1.0
 
  198         """ Convert an ticks to angle, applying limits. """ 
  205         """ Convert speed in radians per second to ticks, applying limits. """ 
  207         if ticks >= self.
ticks:
 
  208             return self.
ticks-1.0
 
  214         """ Turn on/off servo torque, so that it is pose-able. """ 
  223         return EnableResponse(self.
enabled)
 
  226         """ Turn off servo torque, so that it is pose-able. """ 
  231         return RelaxResponse()
 
  234         """ Float64 style command input. """ 
  245         """ Set servo speed. Requested speed is in radians per second. 
  246             Don't allow 0 which means "max speed" to a Dynamixel in joint mode. """ 
  248             ticks_per_sec = max(1, int(self.
speedToTicks(req.speed)))
 
  249             self.
device.setSpeed(self.
id, ticks_per_sec)
 
  250         return SetSpeedResponse()
 
  255         Joint.__init__(self, device, name)
 
  258         self.
id = int(rospy.get_param(n+
"id"))
 
  259         self.
ticks = rospy.get_param(n+
"ticks", 2000)
 
  260         self.
neutral = rospy.get_param(n+
"neutral", 1500)
 
  261         self.
range = rospy.get_param(n+
"range", 180)
 
  267         self.
max_speed = radians(rospy.get_param(n+
"max_speed",90.0)) 
 
  269         self.
invert = rospy.get_param(n+
"invert",
False)
 
  279         rospy.Subscriber(name+
'/command', Float64, self.
commandCb)
 
  282         """ Get the new position to move to, in ticks. """ 
  305         """ Update angle in radians by reading from servo, or by  
  306             using position passed in from a sync read (in ticks). """ 
  310         """ Set the position that controller is moving to.  
  311             Returns output value in ticks. """ 
  318         """ Get a diagnostics status. """ 
  319         msg = DiagnosticStatus()
 
  321         msg.level = DiagnosticStatus.OK
 
  323         msg.values.append(KeyValue(
"Position", str(self.
position)))
 
  327         """ Convert an angle to ticks, applying limits. """ 
  331         if ticks >= self.
ticks:
 
  332             return self.
ticks-1.0
 
  338         """ Convert an ticks to angle, applying limits. """ 
  345         """ Float64 style command input. """ 
  359         Controller.__init__(self, device, name)
 
  365         for joint 
in device.joints.values():
 
  366             if isinstance(joint, DynamixelServo):
 
  368             elif isinstance(joint, HobbyServo):
 
  371         self.
w_delta = rospy.Duration(1.0/rospy.get_param(
"~write_rate", 10.0))
 
  374         self.
r_delta = rospy.Duration(1.0/rospy.get_param(
"~read_rate", 10.0))
 
  377         rospy.Service(name + 
'/relax_all', Relax, self.
relaxCb)
 
  378         rospy.Service(name + 
'/enable_all', Enable, self.
enableCb)
 
  381         """ Read servo positions, update them. """ 
  382         if rospy.Time.now() > self.
r_next and not self.
fake:
 
  383             if self.
device.use_sync_read:
 
  388                         synclist.append(joint.id)
 
  389                 if len(synclist) > 0:
 
  390                     val = self.
device.syncRead(synclist, P_PRESENT_POSITION_L, 2)
 
  394                                 i = synclist.index(joint.id)*2
 
  395                                 joint.setCurrentFeedback(val[i]+(val[i+1]<<8))
 
  402                     joint.setCurrentFeedback(self.
device.getPosition(joint.id))
 
  405         if rospy.Time.now() > self.
w_next:
 
  406             if self.
device.use_sync_write 
and not self.
fake:
 
  409                     v = joint.interpolate(1.0/self.
w_delta.to_sec())
 
  411                         syncpkt.append([joint.id,int(v)%256,int(v)>>8])                         
 
  413                     self.
device.syncWrite(P_GOAL_POSITION_L,syncpkt)
 
  416                     v = joint.interpolate(1.0/self.
w_delta.to_sec())
 
  418                         self.
device.setPosition(joint.id, int(v))
 
  420                 v = joint.interpolate(1.0/self.
w_delta.to_sec())
 
  422                     self.
device.setServo(joint.id, v)
 
  426         """ Update status of servos (voltages, temperatures). """ 
  427         if self.
iter % 5 == 0 
and not self.
fake:
 
  428             if self.
device.use_sync_read:
 
  433                         synclist.append(joint.id)
 
  434                 if len(synclist) > 0:
 
  435                     val = self.
device.syncRead(synclist, P_PRESENT_VOLTAGE, 2)
 
  439                                 i = synclist.index(joint.id)*2
 
  441                                     joint.voltage = val[i]/10.0
 
  443                                     joint.temperature = val[i+1]
 
  451                         val = self.
device.read(joint.id, P_PRESENT_VOLTAGE, 2)
 
  453                             joint.voltage = val[0]
 
  454                             joint.temperature = val[1]
 
  461         """ Turn on/off all servos torque, so that they are pose-able. """ 
  463             resp = joint.enableCb(req)
 
  467         """ Turn off all servos torque, so that they are pose-able. """ 
  469             resp = joint.relaxCb(req)