min_max_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 nav_msgs.msg import Odometry
35 
36 lin_min = 0.0
37 lin_max = 0.0
38 ang_min = 0.0
39 ang_max = 0.0
40 
41 
42 def odom_cb(msg):
43  global lin_min, lin_max, ang_min, ang_max
44  if lin_min > msg.twist.twist.linear.x:
45  lin_min = msg.twist.twist.linear.x
46  if lin_max < msg.twist.twist.linear.x:
47  lin_max = msg.twist.twist.linear.x
48  if ang_min > msg.twist.twist.angular.z:
49  ang_min = msg.twist.twist.angular.z
50  if ang_max < msg.twist.twist.angular.z:
51  ang_max = msg.twist.twist.angular.z
52 
53  rospy.loginfo('linear: [%f, %f] angular: [%f, %f]', lin_min, lin_max, ang_min, ang_max)
54 
55 
56 def main():
57  rospy.init_node('min_max_finder', anonymous=True)
58  rospy.Subscriber('odom', Odometry, odom_cb)
59  rospy.loginfo('min_max_finde node ready and listening. now use teleop to move your robot to the limits!')
60  rospy.spin()
61 
62 
63 if __name__ == '__main__':
64  main()
min_max_finder.odom_cb
def odom_cb(msg)
Definition: min_max_finder.py:42
min_max_finder.main
def main()
Definition: min_max_finder.py:56


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