4   diff_controller.py - controller for a differential drive 
    5   Copyright (c) 2010-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. 
   32 from math 
import sin,cos,pi
 
   34 from geometry_msgs.msg 
import Quaternion
 
   35 from geometry_msgs.msg 
import Twist
 
   36 from nav_msgs.msg 
import Odometry
 
   38 from tf.broadcaster 
import TransformBroadcaster
 
   42 from struct 
import unpack
 
   45     """ Controller to handle movement & odometry feedback for a differential  
   46             drive mobile base. """ 
   48         Controller.__init__(self, device, name)
 
   53         self.
rate = rospy.get_param(
'~controllers/'+name+
'/rate',10.0)
 
   54         self.
timeout = rospy.get_param(
'~controllers/'+name+
'/timeout',1.0)
 
   57         self.
ticks_meter = float(rospy.get_param(
'~controllers/'+name+
'/ticks_meter'))
 
   58         self.
base_width = float(rospy.get_param(
'~controllers/'+name+
'/base_width'))
 
   60         self.
base_frame_id = rospy.get_param(
'~controllers/'+name+
'/base_frame_id', 
'base_link')
 
   61         self.
odom_frame_id = rospy.get_param(
'~controllers/'+name+
'/odom_frame_id', 
'odom')
 
   64         self.
Kp = rospy.get_param(
'~controllers/'+name+
'/Kp', 5)
 
   65         self.
Kd = rospy.get_param(
'~controllers/'+name+
'/Kd', 1)
 
   66         self.
Ki = rospy.get_param(
'~controllers/'+name+
'/Ki', 0)
 
   67         self.
Ko = rospy.get_param(
'~controllers/'+name+
'/Ko', 50)
 
   70         self.
accel_limit = rospy.get_param(
'~controllers/'+name+
'/accel_limit', 0.1)
 
   74         self.
joint_names = [
"base_l_wheel_joint",
"base_r_wheel_joint"]
 
   90         self.
then = rospy.Time.now()    
 
   93         rospy.Subscriber(
"cmd_vel", Twist, self.
cmdVelCb)
 
   94         self.
odomPub = rospy.Publisher(
"odom", Odometry, queue_size=5)
 
   97         rospy.loginfo(
"Started DiffController ("+name+
"). Geometry: " + str(self.
base_width) + 
"m wide, " + str(self.
ticks_meter) + 
" ticks/m.")
 
  104         now = rospy.Time.now()
 
  106             elapsed = now - self.
then 
  108             elapsed = elapsed.to_sec()
 
  111                 x = cos(self.
th)*self.
dx*elapsed
 
  112                 y = -sin(self.
th)*self.
dx*elapsed
 
  113                 self.
x += cos(self.
th)*self.
dx*elapsed
 
  114                 self.
y += sin(self.
th)*self.
dx*elapsed
 
  115                 self.
th += self.
dr*elapsed
 
  119                     left, right = self.
status()
 
  120                 except Exception 
as e:
 
  121                     rospy.logerr(
"Could not update encoders: " + str(e))
 
  123                 rospy.logdebug(
"Encoders: " + str(left) +
","+ str(right))
 
  135                 d = (d_left+d_right)/2
 
  137                 self.
dx = d / elapsed
 
  138                 self.
dr = th / elapsed
 
  143                     self.
x = self.
x + (cos(self.
th)*x - sin(self.
th)*y)
 
  144                     self.
y = self.
y + (sin(self.
th)*x + cos(self.
th)*y)
 
  146                     self.
th = self.
th + th
 
  149             quaternion = Quaternion()
 
  152             quaternion.z = sin(self.
th/2)
 
  153             quaternion.w = cos(self.
th/2)
 
  156                 (quaternion.x, quaternion.y, quaternion.z, quaternion.w),
 
  163             odom.header.stamp = now
 
  165             odom.pose.pose.position.x = self.
x 
  166             odom.pose.pose.position.y = self.
y 
  167             odom.pose.pose.position.z = 0
 
  168             odom.pose.pose.orientation = quaternion
 
  170             odom.twist.twist.linear.x = self.
dx 
  171             odom.twist.twist.linear.y = 0
 
  172             odom.twist.twist.angular.z = self.
dr 
  207         """ Handle movement requests. """ 
  210             self.
dx = req.linear.x        
 
  211             self.
dr = req.angular.z       
 
  218         """ Get a diagnostics status. """ 
  219         msg = DiagnosticStatus()
 
  221         msg.level = DiagnosticStatus.OK
 
  224             msg.values.append(KeyValue(
"Left", str(self.
enc_left)))
 
  225             msg.values.append(KeyValue(
"Right", str(self.
enc_right)))
 
  226         msg.values.append(KeyValue(
"dX", str(self.
dx)))
 
  227         msg.values.append(KeyValue(
"dR", str(self.
dr)))
 
  241         success = self.
device.execute(253, AX_CONTROL_SETUP, [10, kp, kd, ki, ko])
 
  244         """ Send a closed-loop speed. Base PID loop runs at 30Hz, these values 
  245                 are therefore in ticks per 1/30 second. """ 
  248         success = self.
device.execute(253, AX_CONTROL_WRITE, [10, left%256, left>>8, right%256, right>>8])
 
  251         """ read 32-bit (signed) encoder values. """ 
  252         values = self.
device.execute(253, AX_CONTROL_STAT, [10])
 
  253         left_values = 
"".join([chr(k) 
for k 
in values[0:4] ])        
 
  254         right_values = 
"".join([chr(k) 
for k 
in values[4:] ])
 
  256             left = unpack(
'=l',left_values)[0]
 
  257             right = unpack(
'=l',right_values)[0]