base_controller.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 """
00004     A base controller class for the Arduino microcontroller
00005     
00006     Borrowed heavily from Mike Feguson's ArbotiX base_controller.py code.
00007     
00008     Created for the Pi Robot Project: http://www.pirobot.org
00009     Copyright (c) 2010 Patrick Goebel.  All rights reserved.
00010 
00011     This program is free software; you can redistribute it and/or modify
00012     it under the terms of the GNU General Public License as published by
00013     the Free Software Foundation; either version 2 of the License, or
00014     (at your option) any later version.
00015     
00016     This program is distributed in the hope that it will be useful,
00017     but WITHOUT ANY WARRANTY; without even the implied warranty of
00018     MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00019     GNU General Public License for more details at:
00020     
00021     http://www.gnu.org/licenses
00022 """
00023 import roslib; roslib.load_manifest('ros_arduino_python')
00024 import rospy
00025 import os
00026 
00027 from math import sin, cos, pi
00028 from geometry_msgs.msg import Quaternion, Twist, Pose
00029 from nav_msgs.msg import Odometry
00030 from tf.broadcaster import TransformBroadcaster
00031  
00032 """ Class to receive Twist commands and publish Odometry data """
00033 class BaseController:
00034     def __init__(self, arduino):
00035         self.arduino = arduino
00036         self.rate = float(rospy.get_param("~base_controller_rate", 10))
00037         self.timeout = rospy.get_param('~base_controller_timeout', 1.0)
00038         self.stopped = False
00039                  
00040         pid_params = dict()
00041         pid_params['wheel_diameter'] = rospy.get_param("~wheel_diameter", "") 
00042         pid_params['wheel_track'] = rospy.get_param("~wheel_track", "")
00043         pid_params['encoder_resolution'] = rospy.get_param("~encoder_resolution", "") 
00044         pid_params['gear_reduction'] = rospy.get_param("~gear_reduction", 1.0)
00045         pid_params['Kp'] = rospy.get_param("~Kp", 20)
00046         pid_params['Kd'] = rospy.get_param("~Kd", 12)
00047         pid_params['Ki'] = rospy.get_param("~Ki", 0)
00048         pid_params['Ko'] = rospy.get_param("~Ko", 50)
00049         
00050         self.accel_limit = rospy.get_param('~accel_limit', 0.1)
00051         self.motors_reversed = rospy.get_param("~motors_reversed", False)
00052         
00053         # Set up PID parameters and check for missing values
00054         self.setup_pid(pid_params)
00055             
00056         # How many encoder ticks are there per meter?
00057         self.ticks_per_meter = self.encoder_resolution * self.gear_reduction  / (self.wheel_diameter * pi)
00058         
00059         # What is the maximum acceleration we will tolerate when changing wheel speeds?
00060         self.max_accel = self.accel_limit * self.ticks_per_meter / self.rate
00061                 
00062         # Track how often we get a bad encoder count (if any)
00063         self.bad_encoder_count = 0
00064                         
00065         now = rospy.Time.now()    
00066         self.then = now # time for determining dx/dy
00067         self.t_delta = rospy.Duration(1.0 / self.rate)
00068         self.t_next = now + self.t_delta
00069 
00070         # internal data        
00071         self.enc_left = None            # encoder readings
00072         self.enc_right = None
00073         self.x = 0                      # position in xy plane
00074         self.y = 0
00075         self.th = 0                     # rotation in radians
00076         self.v_left = 0
00077         self.v_right = 0
00078         self.v_des_left = 0             # cmd_vel setpoint
00079         self.v_des_right = 0
00080         self.last_cmd_vel = now
00081 
00082         # subscriptions
00083         rospy.Subscriber("cmd_vel", Twist, self.cmdVelCallback)
00084         
00085         # Clear any old odometry info
00086         self.arduino.reset_encoders()
00087         
00088         # Set up the odometry broadcaster
00089         self.odomPub = rospy.Publisher('odom', Odometry)
00090         self.odomBroadcaster = TransformBroadcaster()
00091         
00092         rospy.loginfo("Started base controller for a base of " + str(self.wheel_track) + "m wide with " + str(self.encoder_resolution) + " ticks per rev")
00093         rospy.loginfo("Publishing odometry data at: " + str(self.rate) + " Hz")
00094         
00095     def setup_pid(self, pid_params):
00096         # Check to see if any PID parameters are missing
00097         missing_params = False
00098         for param in pid_params:
00099             if pid_params[param] == "":
00100                 print("*** PID Parameter " + param + " is missing. ***")
00101                 missing_params = True
00102         
00103         if missing_params:
00104             os._exit(1)
00105                 
00106         self.wheel_diameter = pid_params['wheel_diameter']
00107         self.wheel_track = pid_params['wheel_track']
00108         self.encoder_resolution = pid_params['encoder_resolution']
00109         self.gear_reduction = pid_params['gear_reduction']
00110         
00111         self.Kp = pid_params['Kp']
00112         self.Kd = pid_params['Kd']
00113         self.Ki = pid_params['Ki']
00114         self.Ko = pid_params['Ko']
00115         
00116         self.arduino.update_pid(self.Kp, self.Kd, self.Ki, self.Ko)
00117 
00118     def poll(self):
00119         now = rospy.Time.now()
00120         if now > self.t_next:
00121             # Read the encoders
00122             try:
00123                 left_enc, right_enc = self.arduino.get_encoder_counts()
00124             except:
00125                 self.bad_encoder_count += 1
00126                 rospy.logerr("Encoder exception count: " + str(self.bad_encoder_count))
00127                 return
00128                             
00129             dt = now - self.then
00130             self.then = now
00131             dt = dt.to_sec()
00132             
00133             # calculate odometry
00134             if self.enc_left == None:
00135                 dright = 0
00136                 dleft = 0
00137             else:
00138                 dright = (right_enc - self.enc_right) / self.ticks_per_meter
00139                 dleft = (left_enc - self.enc_left) / self.ticks_per_meter
00140 
00141             self.enc_right = right_enc
00142             self.enc_left = left_enc
00143             
00144             dxy_ave = (dright + dleft) / 2.0
00145             dth = (dright - dleft) / self.wheel_track
00146             vxy = dxy_ave / dt
00147             vth = dth / dt
00148                 
00149             if (dxy_ave != 0):
00150                 dx = cos(dth) * dxy_ave
00151                 dy = -sin(dth) * dxy_ave
00152                 self.x += (cos(self.th) * dx - sin(self.th) * dy)
00153                 self.y += (sin(self.th) * dx + cos(self.th) * dy)
00154     
00155             if (dth != 0):
00156                 self.th += dth 
00157     
00158             quaternion = Quaternion()
00159             quaternion.x = 0.0 
00160             quaternion.y = 0.0
00161             quaternion.z = sin(self.th / 2.0)
00162             quaternion.w = cos(self.th / 2.0)
00163     
00164             # Create the odometry transform frame broadcaster.
00165             self.odomBroadcaster.sendTransform(
00166                 (self.x, self.y, 0), 
00167                 (quaternion.x, quaternion.y, quaternion.z, quaternion.w),
00168                 rospy.Time.now(),
00169                 "base_link",
00170                 "odom"
00171                 )
00172     
00173             odom = Odometry()
00174             odom.header.frame_id = "odom"
00175             odom.child_frame_id = "base_link"
00176             odom.header.stamp = now
00177             odom.pose.pose.position.x = self.x
00178             odom.pose.pose.position.y = self.y
00179             odom.pose.pose.position.z = 0
00180             odom.pose.pose.orientation = quaternion
00181             odom.twist.twist.linear.x = vxy
00182             odom.twist.twist.linear.y = 0
00183             odom.twist.twist.angular.z = vth
00184 
00185             self.odomPub.publish(odom)
00186             
00187             if now > (self.last_cmd_vel + rospy.Duration(self.timeout)):
00188                 self.v_des_left = 0
00189                 self.v_des_right = 0
00190                 
00191             if self.v_left < self.v_des_left:
00192                 self.v_left += self.max_accel
00193                 if self.v_left > self.v_des_left:
00194                     self.v_left = self.v_des_left
00195             else:
00196                 self.v_left -= self.max_accel
00197                 if self.v_left < self.v_des_left:
00198                     self.v_left = self.v_des_left
00199             
00200             if self.v_right < self.v_des_right:
00201                 self.v_right += self.max_accel
00202                 if self.v_right > self.v_des_right:
00203                     self.v_right = self.v_des_right
00204             else:
00205                 self.v_right -= self.max_accel
00206                 if self.v_right < self.v_des_right:
00207                     self.v_right = self.v_des_right
00208             
00209             # Set motor speeds in encoder ticks per PID loop
00210             if not self.stopped:
00211                 self.arduino.drive(self.v_left, self.v_right)
00212                 
00213             self.t_next = now + self.t_delta
00214             
00215     def stop(self):
00216         self.stopped = True
00217         self.arduino.drive(0, 0)
00218             
00219     def cmdVelCallback(self, req):
00220         # Handle velocity-based movement requests
00221         self.last_cmd_vel = rospy.Time.now()
00222         
00223         x = req.linear.x         # m/s
00224         th = req.angular.z       # rad/s
00225 
00226         if x == 0:
00227             # Turn in place
00228             right = th * self.wheel_track  * self.gear_reduction / 2.0
00229             left = -right
00230         elif th == 0:
00231             # Pure forward/backward motion
00232             left = right = x
00233         else:
00234             # Rotation about a point in space
00235             left = x - th * self.wheel_track  * self.gear_reduction / 2.0
00236             right = x + th * self.wheel_track  * self.gear_reduction / 2.0
00237             
00238         self.v_des_left = int(left * self.ticks_per_meter / self.arduino.PID_RATE)
00239         self.v_des_right = int(right * self.ticks_per_meter / self.arduino.PID_RATE)
00240         
00241 
00242         
00243 
00244     
00245 
00246     


ros_arduino_python
Author(s): Patrick Goebel
autogenerated on Thu Nov 21 2013 12:10:08