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


mir_navigation
Author(s): Martin Günther
autogenerated on Sun Feb 14 2021 03:40:24