00001
00002
00003 """
00004 ROS Base Controller Class for the cmRobot Element microcontroller
00005 Borrowed heavily from Mike Feguson's ArbotiX base_controller.py code.
00006
00007 Created for The Pi Robot Project: http://www.pirobot.org
00008 Copyright (c) 2010 Patrick Goebel. All rights reserved.
00009
00010 This program is free software; you can redistribute it and/or modify
00011 it under the terms of the GNU General Public License as published by
00012 the Free Software Foundation; either version 2 of the License, or
00013 (at your option) any later version.
00014
00015 This program is distributed in the hope that it will be useful,
00016 but WITHOUT ANY WARRANTY; without even the implied warranty of
00017 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
00018 GNU General Public License for more details at:
00019
00020 http://www.gnu.org/licenses
00021 """
00022 import roslib; roslib.load_manifest('element')
00023 import rospy
00024
00025 from math import sin, cos, pi
00026 from geometry_msgs.msg import Quaternion
00027 from geometry_msgs.msg import Twist
00028 from geometry_msgs.msg import Pose
00029 from nav_msgs.msg import Odometry
00030 from tf.broadcaster import TransformBroadcaster
00031 import threading
00032
00033 """ Class to send Twist commands and receive Odometry data """
00034 class BaseController:
00035 def __init__(self, controller, thread_queue):
00036 self.controller = controller
00037 self.rate = float(rospy.get_param("~base_controller_rate", 10))
00038 self.interval = 1.0 / self.rate
00039
00040
00041
00042 self.pid_params = dict()
00043 self.pid_params['wheel_diameter'] = rospy.get_param("~wheel_diameter", "")
00044 self.pid_params['wheel_track'] = rospy.get_param("~wheel_track", "")
00045 self.pid_params['encoder_type'] = rospy.get_param("~encoder_type", 1)
00046 self.pid_params['encoder_resolution'] = rospy.get_param("~encoder_resolution", "")
00047 self.pid_params['gear_reduction'] = rospy.get_param("~gear_reduction", 1.0)
00048 self.pid_params['motors_reversed'] = rospy.get_param("~motors_reversed", False)
00049
00050 self.pid_params['init_pid'] = rospy.get_param("~init_pid", False)
00051 self.pid_params['VPID_P'] = rospy.get_param("~VPID_P", "")
00052 self.pid_params['VPID_I'] = rospy.get_param("~VPID_I", "")
00053 self.pid_params['VPID_D'] = rospy.get_param("~VPID_D", "")
00054 self.pid_params['VPID_L'] = rospy.get_param("~VPID_L", "")
00055 self.pid_params['DPID_P'] = rospy.get_param("~DPID_P", "")
00056 self.pid_params['DPID_I'] = rospy.get_param("~DPID_I", "")
00057 self.pid_params['DPID_D'] = rospy.get_param("~DPID_D", "")
00058 self.pid_params['DPID_A'] = rospy.get_param("~DPID_A", "")
00059 self.pid_params['DPID_B'] = rospy.get_param("~DPID_B", "")
00060
00061 self.controller.setup_base_controller(self.pid_params)
00062
00063 self.ticks_per_meter = float(self.controller.ticks_per_meter)
00064 self.wheel_track = self.controller.wheel_track
00065 self.gear_reduction = self.controller.gear_reduction
00066 self.encoder_resolution = self.controller.encoder_resolution
00067 self.bad_encoder_count = 0
00068
00069 now = rospy.Time.now()
00070 self.then = now
00071
00072
00073 self.enc_left = None
00074 self.enc_right = None
00075 self.x = 0
00076 self.y = 0
00077 self.th = 0
00078
00079
00080 rospy.Subscriber("cmd_vel", Twist, self.cmdVelCallback)
00081
00082
00083 self.controller.clear_encoder([1, 2])
00084
00085
00086 self.odomPub = rospy.Publisher('odom', Odometry)
00087 self.odomBroadcaster = TransformBroadcaster()
00088
00089 rospy.loginfo("Started base controller for a base of " + str(self.wheel_track) + "m wide with " + str(self.ticks_per_meter) + " ticks per meter")
00090 rospy.loginfo("Publishing odometry data at: " + str(self.rate) + " Hz")
00091
00092 def poll_odom(self, thread_queue):
00093 t = threading.Timer(self.interval, self.poll_odom, [thread_queue])
00094 t.daemon = True
00095 t.start()
00096 thread_queue.put(self.get_odom)
00097
00098 def get_odom(self):
00099 now = rospy.Time.now()
00100
00101
00102 try:
00103 right_enc, left_enc = self.controller.get_encoder_count([1, 2])
00104 except:
00105 self.bad_encoder_count += 1
00106 rospy.logerr("Encoder exception count: " + str(self.bad_encoder_count))
00107 return
00108
00109
00110
00111 dt = now - self.then
00112 self.then = now
00113 dt = dt.to_sec()
00114
00115
00116 if self.enc_left == None:
00117 dleft = 0
00118 dright = 0
00119 else:
00120 dleft = (left_enc - self.enc_left) / self.ticks_per_meter
00121 dright = (right_enc - self.enc_right) / self.ticks_per_meter
00122
00123 self.enc_left = left_enc
00124 self.enc_right = right_enc
00125
00126 dxy_ave = (dleft + dright) / 2.0
00127 dth = (dright - dleft) / self.wheel_track
00128 vxy = dxy_ave / dt
00129 vth = dth / dt
00130
00131 if (dxy_ave != 0):
00132 dx = cos(dth) * dxy_ave
00133 dy = -sin(dth) * dxy_ave
00134 self.x += (cos(self.th) * dx - sin(self.th) * dy)
00135 self.y += (sin(self.th) * dx + cos(self.th) * dy)
00136
00137 if (dth != 0):
00138 self.th += dth
00139
00140 quaternion = Quaternion()
00141 quaternion.x = 0.0
00142 quaternion.y = 0.0
00143 quaternion.z = sin(self.th / 2.0)
00144 quaternion.w = cos(self.th / 2.0)
00145
00146
00147 self.odomBroadcaster.sendTransform(
00148 (self.x, self.y, 0),
00149 (quaternion.x, quaternion.y, quaternion.z, quaternion.w),
00150 rospy.Time.now(),
00151 "base_link",
00152 "odom"
00153 )
00154
00155 odom = Odometry()
00156 odom.header.frame_id = "odom"
00157 odom.child_frame_id = "base_link"
00158 odom.header.stamp = now
00159 odom.pose.pose.position.x = self.x
00160 odom.pose.pose.position.y = self.y
00161 odom.pose.pose.position.z = 0
00162 odom.pose.pose.orientation = quaternion
00163 odom.twist.twist.linear.x = vxy
00164 odom.twist.twist.linear.y = 0
00165 odom.twist.twist.angular.z = vth
00166
00167 self.odomPub.publish(odom)
00168
00169
00170 def cmdVelCallback(self, req):
00171
00172 x = req.linear.x
00173 th = req.angular.z
00174
00175 if x == 0:
00176
00177 right = th * self.wheel_track * self.gear_reduction / 2.0
00178 left = -right
00179 elif th == 0:
00180
00181 left = right = x
00182 else:
00183
00184 left = x - th * self.wheel_track * self.gear_reduction / 2.0
00185 right = x + th * self.wheel_track * self.gear_reduction / 2.0
00186
00187
00188 right = -right
00189
00190
00191 self.controller.mogo_m_per_s([1, 2], [right, left])
00192
00193 def stop(self):
00194 print "Shutting down base controller"
00195
00196
00197
00198
00199
00200