acc_finder.py
Go to the documentation of this file.
1 #!/usr/bin/env python3
2 # Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors
3 #
4 # Redistribution and use in source and binary forms, with or without
5 # modification, are permitted provided that the following conditions are met:
6 #
7 # * Redistributions of source code must retain the above copyright
8 # notice, this list of conditions and the following disclaimer.
9 #
10 # * Redistributions in binary form must reproduce the above copyright
11 # notice, this list of conditions and the following disclaimer in the
12 # documentation and/or other materials provided with the distribution.
13 #
14 # * Neither the name of the copyright holder nor the names of its
15 # contributors may be used to endorse or promote products derived from
16 # this software without specific prior written permission.
17 #
18 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
22 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28 # POSSIBILITY OF SUCH DAMAGE.
29 #
30 # Author: Martin Günther
31 
32 import rospy
33 
34 from geometry_msgs.msg import Twist
35 from nav_msgs.msg import Odometry
36 
37 LIN_MAX = 1.0
38 ANG_MAX = 1.5 # adjust this value to the rough maximum angular velocity
39 
40 state = 'stopped'
41 start = rospy.Time(0)
42 
43 
44 def odom_cb(msg):
45  global state
46 
47  twist = msg.twist.twist
48  t = (rospy.Time.now() - start).to_sec()
49 
50  if state == 'wait_for_stop':
51  if -0.05 < twist.linear.x < 0.05 and -0.1 < twist.angular.z < 0.1:
52  state = 'stopped'
53  rospy.loginfo('state transition --> %s', state)
54  return
55 
56  if state == 'backward' and twist.linear.x < -0.9 * LIN_MAX:
57  rospy.loginfo('backward from 0 to %f m/s in %f sec', twist.linear.x, t)
58  elif state == 'forward' and twist.linear.x > 0.9 * LIN_MAX:
59  rospy.loginfo('forward from 0 to %f m/s in %f sec', twist.linear.x, t)
60  elif state == 'turning_clockwise' and twist.angular.z < -0.9 * ANG_MAX:
61  rospy.loginfo('turning_clockwise from 0 to %f rad/s in %f sec', twist.angular.z, t)
62  elif state == 'turning_counter_clockwise' and twist.angular.z > 0.9 * ANG_MAX:
63  rospy.loginfo('turning_counter_clockwise from 0 to %f rad/s in %f sec', twist.angular.z, t)
64  else:
65  return
66 
67  state = 'wait_for_stop'
68  rospy.loginfo('state transition --> %s', state)
69 
70 
71 def cmd_vel_cb(msg):
72  global state, start
73 
74  if state != 'stopped':
75  return
76 
77  if msg.linear.x <= -LIN_MAX:
78  start = rospy.Time.now()
79  state = 'backward'
80  elif msg.linear.x >= LIN_MAX:
81  start = rospy.Time.now()
82  state = 'forward'
83  elif msg.angular.z <= -ANG_MAX:
84  start = rospy.Time.now()
85  state = 'turning_clockwise'
86  elif msg.angular.z >= ANG_MAX:
87  start = rospy.Time.now()
88  state = 'turning_counter_clockwise'
89  else:
90  return
91 
92  rospy.loginfo('state transition --> %s', state)
93 
94 
95 def main():
96  rospy.init_node('acc_finder', anonymous=True)
97  rospy.Subscriber('odom', Odometry, odom_cb)
98  rospy.Subscriber('cmd_vel', Twist, cmd_vel_cb)
99  rospy.loginfo('acc_finder node ready and listening. now use teleop to move your robot to the limits!')
100  rospy.spin()
101 
102 
103 if __name__ == '__main__':
104  main()
acc_finder.main
def main()
Definition: acc_finder.py:95
acc_finder.cmd_vel_cb
def cmd_vel_cb(msg)
Definition: acc_finder.py:71
acc_finder.odom_cb
def odom_cb(msg)
Definition: acc_finder.py:44


mir_navigation
Author(s): Martin Günther
autogenerated on Tue May 13 2025 02:41:48