00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 from __future__ import with_statement
00039
00040 import roslib; roslib.load_manifest('turtlebot_calibration')
00041 import yaml
00042 import PyKDL
00043 import rospy
00044 from sensor_msgs.msg import Imu
00045 from nav_msgs.msg import Odometry
00046 from geometry_msgs.msg import Twist
00047 from turtlebot_calibration.msg import ScanAngle
00048 from math import *
00049 import threading
00050
00051
00052 def quat_to_angle(quat):
00053 rot = PyKDL.Rotation.Quaternion(quat.x, quat.y, quat.z, quat.w)
00054 return rot.GetRPY()[2]
00055
00056 def normalize_angle(angle):
00057 res = angle
00058 while res > pi:
00059 res -= 2.0*pi
00060 while res < -pi:
00061 res += 2.0*pi
00062 return res
00063
00064
00065 class CalibrateRobot:
00066 def __init__(self):
00067 self.lock = threading.Lock()
00068
00069 self.has_gyro = rospy.get_param("turtlebot_node/has_gyro")
00070 rospy.loginfo('has_gyro %s'%self.has_gyro)
00071 if self.has_gyro:
00072 self.sub_imu = rospy.Subscriber('imu', Imu, self.imu_cb)
00073
00074 self.sub_odom = rospy.Subscriber('odom', Odometry, self.odom_cb)
00075 self.sub_scan = rospy.Subscriber('scan_angle', ScanAngle, self.scan_cb)
00076 self.cmd_pub = rospy.Publisher('cmd_vel', Twist)
00077 self.imu_time = rospy.Time()
00078 self.odom_time = rospy.Time()
00079 self.scan_time = rospy.Time()
00080
00081
00082 self.inital_wall_angle = rospy.get_param("inital_wall_angle", 0.1)
00083 self.imu_calibrate_time = rospy.get_param("imu_calibrate_time", 10.0)
00084 self.imu_angle = 0
00085 self.imu_time = rospy.Time.now()
00086 self.scan_angle = 0
00087 self.scan_time = rospy.Time.now()
00088 self.odom_angle = 0
00089 self.odom_time = rospy.Time.now()
00090
00091 def calibrate(self, speed, imu_drift=0):
00092
00093 (imu_start_angle, odom_start_angle, scan_start_angle,
00094 imu_start_time, odom_start_time, scan_start_time) = self.sync_timestamps()
00095 last_angle = odom_start_angle
00096 turn_angle = 0
00097 while turn_angle < 2*pi:
00098 if rospy.is_shutdown():
00099 return
00100 cmd = Twist()
00101 cmd.angular.z = speed
00102 self.cmd_pub.publish(cmd)
00103 rospy.sleep(0.1)
00104 with self.lock:
00105 delta_angle = normalize_angle(self.odom_angle - last_angle)
00106 turn_angle += delta_angle
00107 last_angle = self.odom_angle
00108 self.cmd_pub.publish(Twist())
00109
00110 (imu_end_angle, odom_end_angle, scan_end_angle,
00111 imu_end_time, odom_end_time, scan_end_time) = self.sync_timestamps()
00112
00113 scan_delta = 2*pi + normalize_angle(scan_end_angle - scan_start_angle)
00114
00115 odom_delta = 2*pi + normalize_angle(odom_end_angle - odom_start_angle)
00116 rospy.loginfo('Odom error: %f percent'%(100.0*((odom_delta/scan_delta)-1.0)))
00117
00118 if self.has_gyro:
00119 imu_delta = 2*pi + normalize_angle(imu_end_angle - imu_start_angle) - imu_drift*(imu_end_time - imu_start_time).to_sec()
00120 rospy.loginfo('Imu error: %f percent'%(100.0*((imu_delta/scan_delta)-1.0)))
00121 imu_result = imu_delta/scan_delta
00122 else:
00123 imu_result = None
00124
00125 return (imu_result, odom_delta/scan_delta)
00126
00127
00128 def imu_drift(self):
00129 if not self.has_gyro:
00130 return 0
00131
00132 rospy.loginfo('Estimating imu drift')
00133 (imu_start_angle, odom_start_angle, scan_start_angle,
00134 imu_start_time, odom_start_time, scan_start_time) = self.sync_timestamps()
00135 rospy.sleep(self.imu_calibrate_time)
00136 (imu_end_angle, odom_end_angle, scan_end_angle,
00137 imu_end_time, odom_end_time, scan_end_time) = self.sync_timestamps()
00138
00139 imu_drift = normalize_angle(imu_end_angle - imu_start_angle) / ((imu_end_time - imu_start_time).to_sec())
00140 rospy.loginfo(' ... imu drift is %f degrees per second'%(imu_drift*180.0/pi))
00141 return imu_drift
00142
00143
00144 def align(self):
00145 self.sync_timestamps()
00146 rospy.loginfo("Aligning base with wall")
00147 with self.lock:
00148 angle = self.scan_angle
00149 cmd = Twist()
00150
00151 while angle < -self.inital_wall_angle or angle > self.inital_wall_angle:
00152 if rospy.is_shutdown():
00153 exit(0)
00154 if angle > 0:
00155 cmd.angular.z = -0.3
00156 else:
00157 cmd.angular.z = 0.3
00158 self.cmd_pub.publish(cmd)
00159 rospy.sleep(0.05)
00160 with self.lock:
00161 angle = self.scan_angle
00162
00163
00164
00165 def sync_timestamps(self, start_time=None):
00166 if not start_time:
00167 start_time = rospy.Time.now() + rospy.Duration(0.5)
00168 while not rospy.is_shutdown():
00169 rospy.sleep(0.3)
00170 with self.lock:
00171 if self.imu_time < start_time and self.has_gyro:
00172 rospy.loginfo("Still waiting for imu")
00173 elif self.odom_time < start_time:
00174 rospy.loginfo("Still waiting for odom")
00175 elif self.scan_time < start_time:
00176 rospy.loginfo("Still waiting for scan")
00177 else:
00178 return (self.imu_angle, self.odom_angle, self.scan_angle,
00179 self.imu_time, self.odom_time, self.scan_time)
00180 exit(0)
00181
00182
00183 def imu_cb(self, msg):
00184 with self.lock:
00185 angle = quat_to_angle(msg.orientation)
00186 self.imu_angle = angle
00187 self.imu_time = msg.header.stamp
00188
00189 def odom_cb(self, msg):
00190 with self.lock:
00191 angle = quat_to_angle(msg.pose.pose.orientation)
00192 self.odom_angle = angle
00193 self.odom_time = msg.header.stamp
00194
00195 def scan_cb(self, msg):
00196 with self.lock:
00197 angle = msg.scan_angle
00198 self.scan_angle = angle
00199 self.scan_time = msg.header.stamp
00200
00201
00202
00203 def main():
00204 rospy.init_node('scan_to_angle')
00205 robot = CalibrateRobot()
00206
00207 imu_drift = robot.imu_drift()
00208 imu_corr = []
00209 odom_corr = []
00210 for speed in (0.3, 0.7, 1.0, 1.5):
00211 robot.align()
00212 (imu, odom) = robot.calibrate(speed, imu_drift)
00213 if imu:
00214 imu_corr.append(imu)
00215 odom_corr.append(odom)
00216
00217 if len(imu_corr)>0:
00218 imu_res = 1.0/(sum(imu_corr)/len(imu_corr))
00219 rospy.loginfo("Multiply the 'turtlebot_node/gyro_scale_correction' parameter with %f"%imu_res)
00220
00221 odom_res = 1.0/(sum(odom_corr)/len(odom_corr))
00222 rospy.loginfo("Multiply the 'turtlebot_node/odom_angular_scale_correction' parameter with %f"%odom_res)
00223
00224
00225 if __name__ == '__main__':
00226 main()