00001
00002
00003 """
00004 diff_controller.py - controller for a differential drive
00005 Copyright (c) 2010-2011 Vanadium Labs LLC. All right reserved.
00006
00007 Redistribution and use in source and binary forms, with or without
00008 modification, are permitted provided that the following conditions are met:
00009 * Redistributions of source code must retain the above copyright
00010 notice, this list of conditions and the following disclaimer.
00011 * Redistributions in binary form must reproduce the above copyright
00012 notice, this list of conditions and the following disclaimer in the
00013 documentation and/or other materials provided with the distribution.
00014 * Neither the name of Vanadium Labs LLC nor the names of its
00015 contributors may be used to endorse or promote products derived
00016 from this software without specific prior written permission.
00017
00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00019 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 DISCLAIMED. IN NO EVENT SHALL VANADIUM LABS BE LIABLE FOR ANY DIRECT, INDIRECT,
00022 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00023 LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
00024 OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00025 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00026 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00027 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 """
00029
00030 import rospy
00031
00032 from math import sin,cos,pi
00033
00034 from geometry_msgs.msg import Quaternion
00035 from geometry_msgs.msg import Twist
00036 from nav_msgs.msg import Odometry
00037 from diagnostic_msgs.msg import *
00038 from tf.broadcaster import TransformBroadcaster
00039
00040 from ax12 import *
00041 from struct import unpack
00042
00043 class DiffController:
00044 """ Controller to handle movement & odometry feedback for a differential
00045 drive mobile base. """
00046 def __init__(self, device, name):
00047 self.name = name
00048 self.device = device
00049 self.fake = device.fake
00050 self.last_cmd = rospy.Time.now()
00051
00052
00053 self.rate = rospy.get_param('~controllers/'+name+'/rate',10.0)
00054 self.timeout = rospy.get_param('~controllers/'+name+'/timeout',1.0)
00055 self.t_delta = rospy.Duration(1.0/self.rate)
00056 self.t_next = rospy.Time.now() + self.t_delta
00057 self.ticks_meter = float(rospy.get_param('~controllers/'+name+'/ticks_meter'))
00058 self.base_width = float(rospy.get_param('~controllers/'+name+'/base_width'))
00059
00060
00061 self.Kp = rospy.get_param('~controllers/'+name+'/Kp', 5)
00062 self.Kd = rospy.get_param('~controllers/'+name+'/Kd', 1)
00063 self.Ki = rospy.get_param('~controllers/'+name+'/Ki', 0)
00064 self.Ko = rospy.get_param('~controllers/'+name+'/Ko', 50)
00065
00066
00067 self.accel_limit = rospy.get_param('~controllers/'+name+'/accel_limit', 0.1)
00068 self.max_accel = int(self.accel_limit*self.ticks_meter/self.rate)
00069
00070
00071 self.joint_names = ["base_l_wheel_joint","base_r_wheel_joint"]
00072 self.joint_positions = [0,0]
00073 self.joint_velocities = [0,0]
00074
00075
00076 self.v_left = 0
00077 self.v_right = 0
00078 self.v_des_left = 0
00079 self.v_des_right = 0
00080 self.enc_left = None
00081 self.enc_right = None
00082 self.x = 0
00083 self.y = 0
00084 self.th = 0
00085 self.dx = 0
00086 self.dr = 0
00087 self.then = rospy.Time.now()
00088
00089
00090 rospy.Subscriber("cmd_vel", Twist, self.cmdVelCb)
00091 self.odomPub = rospy.Publisher("odom",Odometry)
00092 self.odomBroadcaster = TransformBroadcaster()
00093
00094 rospy.loginfo("Started DiffController ("+name+"). Geometry: " + str(self.base_width) + "m wide, " + str(self.ticks_meter) + " ticks/m.")
00095
00096 def startup(self):
00097 if not self.fake:
00098 self.setup(self.Kp,self.Kd,self.Ki,self.Ko)
00099
00100 def update(self):
00101 now = rospy.Time.now()
00102 if now > self.t_next:
00103 elapsed = now - self.then
00104 self.then = now
00105 elapsed = elapsed.to_sec()
00106
00107 if self.fake:
00108 x = cos(self.th)*self.dx*elapsed
00109 y = -sin(self.th)*self.dx*elapsed
00110 self.x += cos(self.th)*self.dx*elapsed
00111 self.y += sin(self.th)*self.dx*elapsed
00112 self.th += self.dr*elapsed
00113 else:
00114
00115 try:
00116 left, right = self.status()
00117 except Exception as e:
00118 rospy.logerr("Could not update encoders: " + str(e))
00119 return
00120 rospy.logdebug("Encoders: " + str(left) +","+ str(right))
00121
00122
00123 if self.enc_left == None:
00124 d_left = 0
00125 d_right = 0
00126 else:
00127 d_left = (left - self.enc_left)/self.ticks_meter
00128 d_right = (right - self.enc_right)/self.ticks_meter
00129 self.enc_left = left
00130 self.enc_right = right
00131
00132 d = (d_left+d_right)/2
00133 th = (d_right-d_left)/self.base_width
00134 self.dx = d / elapsed
00135 self.dr = th / elapsed
00136
00137 if (d != 0):
00138 x = cos(th)*d
00139 y = -sin(th)*d
00140 self.x = self.x + (cos(self.th)*x - sin(self.th)*y)
00141 self.y = self.y + (sin(self.th)*x + cos(self.th)*y)
00142 if (th != 0):
00143 self.th = self.th + th
00144
00145
00146 quaternion = Quaternion()
00147 quaternion.x = 0.0
00148 quaternion.y = 0.0
00149 quaternion.z = sin(self.th/2)
00150 quaternion.w = cos(self.th/2)
00151 self.odomBroadcaster.sendTransform(
00152 (self.x, self.y, 0),
00153 (quaternion.x, quaternion.y, quaternion.z, quaternion.w),
00154 rospy.Time.now(),
00155 "base_link",
00156 "odom"
00157 )
00158
00159 odom = Odometry()
00160 odom.header.frame_id = "odom"
00161 odom.pose.pose.position.x = self.x
00162 odom.pose.pose.position.y = self.y
00163 odom.pose.pose.position.z = 0
00164 odom.pose.pose.orientation = quaternion
00165 odom.child_frame_id = "base_link"
00166 odom.twist.twist.linear.x = self.dx
00167 odom.twist.twist.linear.y = 0
00168 odom.twist.twist.angular.z = self.dr
00169 self.odomPub.publish(odom)
00170
00171 if now > (self.last_cmd + rospy.Duration(self.timeout)):
00172 self.v_des_left = 0
00173 self.v_des_right = 0
00174
00175
00176 if not self.fake:
00177 if self.v_left < self.v_des_left:
00178 self.v_left += self.max_accel
00179 if self.v_left > self.v_des_left:
00180 self.v_left = self.v_des_left
00181 else:
00182 self.v_left -= self.max_accel
00183 if self.v_left < self.v_des_left:
00184 self.v_left = self.v_des_left
00185
00186 if self.v_right < self.v_des_right:
00187 self.v_right += self.max_accel
00188 if self.v_right > self.v_des_right:
00189 self.v_right = self.v_des_right
00190 else:
00191 self.v_right -= self.max_accel
00192 if self.v_right < self.v_des_right:
00193 self.v_right = self.v_des_right
00194 self.write(self.v_left, self.v_right)
00195
00196 self.t_next = now + self.t_delta
00197
00198 def shutdown(self):
00199 if not self.fake:
00200 self.write(0,0)
00201
00202 def cmdVelCb(self,req):
00203 """ Handle movement requests. """
00204 self.last_cmd = rospy.Time.now()
00205 if self.fake:
00206 self.dx = req.linear.x
00207 self.dr = req.angular.z
00208 else:
00209
00210 self.v_des_left = int( ((req.linear.x - (req.angular.z * self.base_width/2.0)) * self.ticks_meter) / 30.0)
00211 self.v_des_right = int( ((req.linear.x + (req.angular.z * self.base_width/2.0)) * self.ticks_meter) / 30.0)
00212
00213 def getDiagnostics(self):
00214 """ Get a diagnostics status. """
00215 msg = DiagnosticStatus()
00216 msg.name = self.name
00217 msg.level = DiagnosticStatus.OK
00218 msg.message = "OK"
00219 if not self.fake:
00220 msg.values.append(KeyValue("Left", str(self.enc_left)))
00221 msg.values.append(KeyValue("Right", str(self.enc_right)))
00222 msg.values.append(KeyValue("dX", str(self.dx)))
00223 msg.values.append(KeyValue("dR", str(self.dr)))
00224 return msg
00225
00226
00227
00228
00229
00230
00231
00232
00233
00234
00235
00236 def setup(self, kp, kd, ki, ko):
00237 success = self.device.execute(253, AX_CONTROL_SETUP, [10, kp, kd, ki, ko])
00238
00239 def write(self, left, right):
00240 """ Send a closed-loop speed. Base PID loop runs at 30Hz, these values
00241 are therefore in ticks per 1/30 second. """
00242 left = left&0xffff
00243 right = right&0xffff
00244 success = self.device.execute(253, AX_CONTROL_WRITE, [10, left%256, left>>8, right%256, right>>8])
00245
00246 def status(self):
00247 """ read 32-bit (signed) encoder values. """
00248 values = self.device.execute(253, AX_CONTROL_STAT, [10])
00249 left_values = "".join([chr(k) for k in values[0:4] ])
00250 right_values = "".join([chr(k) for k in values[4:] ])
00251 try:
00252 left = unpack('=l',left_values)[0]
00253 right = unpack('=l',right_values)[0]
00254 return [left, right]
00255 except:
00256 return None
00257