acc_finder.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import roslib; roslib.load_manifest('acc_finder')
3 import rospy
4 
5 from geometry_msgs.msg import Twist
6 from nav_msgs.msg import Odometry
7 
8 LIN_MAX = 0.75
9 ANG_MAX = 1.0 # adjust this value to the rough maximum angular velocity
10 
11 state = 'stopped'
12 start = rospy.Time(0.0)
13 
14 def odom_cb(msg):
15  global state
16 
17  twist = msg.twist.twist
18  t = (rospy.Time.now() - start).to_sec()
19 
20  if state == 'wait_for_stop':
21  if twist.linear.x > -0.05 and twist.linear.x < 0.05 and twist.angular.z > -0.1 and twist.angular.z < 0.1:
22  state = 'stopped'
23  rospy.loginfo('state transition --> %s', state)
24  return
25 
26  if state == 'backward' and twist.linear.x < -0.9 * LIN_MAX:
27  rospy.loginfo('backward from 0 to %f m/s in %f sec', twist.linear.x, t)
28  elif state == 'forward' and twist.linear.x > 0.9 * LIN_MAX:
29  rospy.loginfo('forward from 0 to %f m/s in %f sec', twist.linear.x, t)
30  elif state == 'turning_clockwise' and twist.angular.z < -0.9 * ANG_MAX:
31  rospy.loginfo('turning_clockwise from 0 to %f rad/s in %f sec', twist.angular.z, t)
32  elif state == 'turning_counter_clockwise' and twist.angular.z > 0.9 * ANG_MAX:
33  rospy.loginfo('turning_counter_clockwise from 0 to %f rad/s in %f sec', twist.angular.z, t)
34  else:
35  return
36 
37  state = 'wait_for_stop'
38  rospy.loginfo('state transition --> %s', state)
39 
40 
41 def cmd_vel_cb(msg):
42  global state, start
43 
44  if state != 'stopped':
45  return
46 
47  if msg.linear.x < -0.5:
48  start = rospy.Time.now()
49  state = 'backward'
50  elif msg.linear.x > 0.5:
51  start = rospy.Time.now()
52  state = 'forward'
53  elif msg.angular.z < -1.0:
54  start = rospy.Time.now()
55  state = 'turning_clockwise'
56  elif msg.angular.z > 1.0:
57  start = rospy.Time.now()
58  state = 'turning_counter_clockwise'
59  else:
60  return
61 
62  rospy.loginfo('state transition --> %s', state)
63 
64 
65 def listener():
66  rospy.init_node('acc_finder', anonymous=True)
67  rospy.Subscriber('odom', Odometry, odom_cb)
68  rospy.Subscriber('cmd_vel', Twist, cmd_vel_cb)
69  rospy.loginfo('acc_finder node ready and listening. now use teleop to move your robot to the limits!')
70  rospy.spin()
71 
72 if __name__ == '__main__':
73  listener()
def odom_cb(msg)
Definition: acc_finder.py:14
def cmd_vel_cb(msg)
Definition: acc_finder.py:41
def listener()
Definition: acc_finder.py:65


acc_finder
Author(s): Martin Guenther
autogenerated on Mon Jun 10 2019 15:49:09