4   linear_controller.py - controller for a linear actuator with analog feedback 
    5   Copyright (c) 2011 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. 
   30 import rospy, actionlib
 
   34 from std_msgs.msg 
import Float64
 
   38 from struct 
import unpack
 
   42         Joint.__init__(self, device, name)
 
   48         self.
last = rospy.Time.now()
 
   51         self.
min = rospy.get_param(
'~joints/'+name+
'/min_position',0.0)
 
   52         self.
max = rospy.get_param(
'~joints/'+name+
'/max_position',0.5)
 
   53         self.
max_speed = rospy.get_param(
'~joints/'+name+
'/max_speed',0.0508)
 
   56         self.
cal = { -1: -1, 1: 1 }
 
   57         self.
cal_raw = rospy.get_param(
'~joints/'+name+
'/calibration_data', self.
cal)
 
   59         for key, value 
in self.
cal_raw.items():
 
   60             self.
cal[int(key)] = value
 
   63         rospy.Subscriber(name+
'/command', Float64, self.
commandCb)
 
   66         """ Get new output: 1 = increase position, -1 is decrease position. """ 
   84         if reading >= self.
keys[0] 
and reading <= self.
keys[-1]:
 
   92             rospy.logerr(self.
name + 
": feedback reading out of range")
 
   95         """ Set the position that controller is moving to.  
   96             Returns output value in raw_data format. """ 
   97         if position <= self.
max and position >= self.
min:
 
  101             rospy.logerr(self.
name + 
": requested position is out of range: " + str(position))
 
  105         """ Get a diagnostics status. """ 
  106         msg = DiagnosticStatus()
 
  108         msg.level = DiagnosticStatus.OK
 
  110             msg.message = 
"Moving" 
  113         msg.values.append(KeyValue(
"Position", str(self.
position)))
 
  117         """ Float64 style command input. """ 
  121             if req.data <= self.
max and req.data >= self.
min:
 
  125                 rospy.logerr(self.
name + 
": requested position is out of range: " + str(req))
 
  129         while reading > self.
keys[low+1]:
 
  131         high = len(self.
keys) - 1
 
  132         while reading < self.
keys[high-1]:
 
  134         x = self.
keys[high] - self.
keys[low]
 
  136         x1 = reading - self.
keys[low]
 
  137         y1 = y * ( float(x1)/float(x) )
 
  138         return self.
cal[self.
keys[low]] + y1
 
  142     """ A controller for a linear actuator, with absolute positional feedback. """ 
  145         Controller.__init__(self, device, name)
 
  147         self.
a = rospy.get_param(
'~controllers/'+name+
'/motor_a',29)
 
  148         self.
b = rospy.get_param(
'~controllers/'+name+
'/motor_b',30)
 
  149         self.
p = rospy.get_param(
'~controllers/'+name+
'/motor_pwm',31)
 
  150         self.
analog = rospy.get_param(
'~controllers/'+name+
'/feedback',0)
 
  154         self.
delta = rospy.Duration(1.0/rospy.get_param(
'~controllers/'+name+
'/rate', 10.0))
 
  157         self.
joint = device.joints[rospy.get_param(
'~controllers/'+name+
'/joint')]
 
  159         rospy.loginfo(
"Started LinearController ("+self.
name+
").")
 
  166         now = rospy.Time.now()
 
  174                     except Exception 
as e:
 
  175                         print(
"linear error: ", e)
 
  177                 output = self.
joint.interpolate(1.0/self.
delta.to_sec())
 
  178                 if self.
last != output 
and not self.
fake: 
 
  184         """ Set speed of actuator. """ 
  186             self.
device.setDigital(self.
a, 0); self.
device.setDigital(self.
b, 1);   
 
  187             self.
device.setDigital(self.
p, 1)
 
  189             self.
device.setDigital(self.
a, 1); self.
device.setDigital(self.
b, 0);   
 
  190             self.
device.setDigital(self.
p, 1)
 
  192             self.
device.setDigital(self.
p, 0)
 
  199             self.
device.setDigital(self.
p, 0)
 
  202         """ Get a diagnostics status. """ 
  203         msg = DiagnosticStatus()
 
  206         msg.level = DiagnosticStatus.OK
 
  209             msg.values.append(KeyValue(
"Encoder Reading", str(self.
last_reading)))
 
  215     """ A controller for a linear actuator, without absolute encoder. """ 
  221         Controller.__init__(self, device, name)
 
  224         self.
a = rospy.get_param(
'~controllers/'+name+
'/motor_a',29)
 
  225         self.
b = rospy.get_param(
'~controllers/'+name+
'/motor_b',30)
 
  226         self.
p = rospy.get_param(
'~controllers/'+name+
'/motor_pwm',31)
 
  230         self.
delta = rospy.Duration(1.0/rospy.get_param(
'~controllers/'+name+
'/rate', 10.0))
 
  233         self.
joint = device.joints[rospy.get_param(
'~controllers/'+name+
'/joint')]
 
  235         rospy.Service(name+
'/zero', Empty, self.
zeroCb)
 
  236         rospy.loginfo(
"Started LinearControllerIncremental ("+self.
name+
").")
 
  243         """ Set speed of actuator. We need to set direction for encoder. """ 
  246             self.
device.setDigital(self.
a, 0); self.
device.setDigital(self.
b, 1);   
 
  247             self.
device.setDigital(self.
p, 1)
 
  250             self.
device.setDigital(self.
a, 1); self.
device.setDigital(self.
b, 0);   
 
  251             self.
device.setDigital(self.
p, 1)
 
  253             self.
device.setDigital(self.
p, 0)
 
  256         return unpack(
'=h', 
"".join([chr(k) 
for k 
in self.
device.read(253, self.
POSITION_L, 2)]) )[0]
 
  259         rospy.loginfo(self.
name + 
': zeroing encoder')
 
  262         for i 
in range(int(timeout)):
 
  263             if rospy.is_shutdown():
 
  269             if last_pos == new_pos:
 
  275         self.
joint.setCurrentFeedback(0)
 
  280         return EmptyResponse()