test_slow_drive.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2012, Yujin Robot
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of the Yujin Robot nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 #
35 # Move following a 90cm radius circle while publishing accumulated and
36 # average error on angular velocity, using gyroscope data as reference
37 # Useful for testing passive wheels configurations
38 # See https://github.com/yujinrobot/kobuki/issues/202 for more details
39 
40 
41 import roslib; roslib.load_manifest('kobuki_testsuite')
42 import rospy
43 import sys
44 
45 from tf.transformations import euler_from_quaternion
46 from math import degrees
47 
48 from sensor_msgs.msg import Imu
49 from std_msgs.msg import Float32
50 from nav_msgs.msg import Odometry
51 from geometry_msgs.msg import Twist
52 from geometry_msgs.msg import Quaternion
53 
54 
56  # constructor
57  def __init__(self):
58  rospy.init_node("test_slow_drive")
59 
60  if (len(sys.argv) > 1):
61  multip = int(sys.argv[1])
62  else:
63  multip = 1
64  self.count = 0
65  self.int_err = 0.0
66  self.avg_err = 0.0
67  self.target_v = 0.09*abs(multip)
68  self.target_w = 0.1*multip
69  self.twist = Twist()
70  self.cmd_vel_pub = rospy.Publisher("/mobile_base/commands/velocity", Twist)
71  self.int_err_pub = rospy.Publisher("/int_err", Float32)
72  self.avg_err_pub = rospy.Publisher("/avg_err", Float32)
73 
74  rospy.Subscriber("/mobile_base/sensors/imu_data", Imu, self.ImuCallback)
75  rospy.Subscriber("/odom", Odometry, self.OdomCallback)
76 
77  def OdomCallback(self, data):
78  self.odom = data.pose.pose.position.x
79 
80  def ImuCallback(self, data):
81  self.count = self.count + 1
82  if (self.count > 100):
83  self.real_w = data.angular_velocity.z
84  self.int_err += abs(self.target_w - self.real_w)
85  self.avg_err = self.int_err/(self.count - 100)
86 
87  self.int_err_pub.publish(self.int_err)
88  self.avg_err_pub.publish(self.avg_err)
89 
90  self.twist.linear.x = self.target_v
91  self.twist.angular.z = self.target_w
92  self.cmd_vel_pub.publish(self.twist)
93 
94 
95 test_slow_drive_obj = Test_slow_drive()
96 
97 while not rospy.is_shutdown():
98  rospy.spin()
99 print ''
100 print test_slow_drive_obj.int_err
101 print test_slow_drive_obj.avg_err
102 print '' # for clean output


kobuki_testsuite
Author(s): Jorge Santos Simon
autogenerated on Mon Jun 10 2019 13:45:22