Go to the documentation of this file.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
00039
00040
00041 import roslib; roslib.load_manifest('kobuki_testsuite')
00042 import rospy
00043 import sys
00044
00045 from tf.transformations import euler_from_quaternion
00046 from math import degrees
00047
00048 from sensor_msgs.msg import Imu
00049 from std_msgs.msg import Float32
00050 from nav_msgs.msg import Odometry
00051 from geometry_msgs.msg import Twist
00052 from geometry_msgs.msg import Quaternion
00053
00054
00055 class Test_slow_drive:
00056
00057 def __init__(self):
00058 rospy.init_node("test_slow_drive")
00059
00060 if (len(sys.argv) > 1):
00061 multip = int(sys.argv[1])
00062 else:
00063 multip = 1
00064 self.count = 0
00065 self.int_err = 0.0
00066 self.avg_err = 0.0
00067 self.target_v = 0.09*abs(multip)
00068 self.target_w = 0.1*multip
00069 self.twist = Twist()
00070 self.cmd_vel_pub = rospy.Publisher("/mobile_base/commands/velocity", Twist)
00071 self.int_err_pub = rospy.Publisher("/int_err", Float32)
00072 self.avg_err_pub = rospy.Publisher("/avg_err", Float32)
00073
00074 rospy.Subscriber("/mobile_base/sensors/imu_data", Imu, self.ImuCallback)
00075 rospy.Subscriber("/odom", Odometry, self.OdomCallback)
00076
00077 def OdomCallback(self, data):
00078 self.odom = data.pose.pose.position.x
00079
00080 def ImuCallback(self, data):
00081 self.count = self.count + 1
00082 if (self.count > 100):
00083 self.real_w = data.angular_velocity.z
00084 self.int_err += abs(self.target_w - self.real_w)
00085 self.avg_err = self.int_err/(self.count - 100)
00086
00087 self.int_err_pub.publish(self.int_err)
00088 self.avg_err_pub.publish(self.avg_err)
00089
00090 self.twist.linear.x = self.target_v
00091 self.twist.angular.z = self.target_w
00092 self.cmd_vel_pub.publish(self.twist)
00093
00094
00095 test_slow_drive_obj = Test_slow_drive()
00096
00097 while not rospy.is_shutdown():
00098 rospy.spin()
00099 print ''
00100 print test_slow_drive_obj.int_err
00101 print test_slow_drive_obj.avg_err
00102 print ''