acc_finder.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import rospy
00004 
00005 from geometry_msgs.msg import Twist
00006 from nav_msgs.msg import Odometry
00007 
00008 LIN_MAX = 1.0
00009 ANG_MAX = 1.5  # adjust this value to the rough maximum angular velocity
00010 
00011 state = 'stopped'
00012 start = rospy.Time(0)
00013 
00014 
00015 def odom_cb(msg):
00016     global state
00017 
00018     twist = msg.twist.twist
00019     t = (rospy.Time.now() - start).to_sec()
00020 
00021     if state == 'wait_for_stop':
00022         if -0.05 < twist.linear.x < 0.05 and -0.1 < twist.angular.z < 0.1:
00023             state = 'stopped'
00024             rospy.loginfo('state transition --> %s', state)
00025         return
00026 
00027     if state == 'backward' and twist.linear.x < -0.9 * LIN_MAX:
00028         rospy.loginfo('backward from 0 to %f m/s in %f sec', twist.linear.x, t)
00029     elif state == 'forward' and twist.linear.x > 0.9 * LIN_MAX:
00030         rospy.loginfo('forward from 0 to %f m/s in %f sec', twist.linear.x, t)
00031     elif state == 'turning_clockwise' and twist.angular.z < -0.9 * ANG_MAX:
00032         rospy.loginfo('turning_clockwise from 0 to %f rad/s in %f sec', twist.angular.z, t)
00033     elif state == 'turning_counter_clockwise' and twist.angular.z > 0.9 * ANG_MAX:
00034         rospy.loginfo('turning_counter_clockwise from 0 to %f rad/s in %f sec', twist.angular.z, t)
00035     else:
00036         return
00037 
00038     state = 'wait_for_stop'
00039     rospy.loginfo('state transition --> %s', state)
00040 
00041 
00042 def cmd_vel_cb(msg):
00043     global state, start
00044 
00045     if state != 'stopped':
00046         return
00047 
00048     if msg.linear.x <= -LIN_MAX:
00049         start = rospy.Time.now()
00050         state = 'backward'
00051     elif msg.linear.x >= LIN_MAX:
00052         start = rospy.Time.now()
00053         state = 'forward'
00054     elif msg.angular.z <= -ANG_MAX:
00055         start = rospy.Time.now()
00056         state = 'turning_clockwise'
00057     elif msg.angular.z >= ANG_MAX:
00058         start = rospy.Time.now()
00059         state = 'turning_counter_clockwise'
00060     else:
00061         return
00062 
00063     rospy.loginfo('state transition --> %s', state)
00064 
00065 
00066 def main():
00067     rospy.init_node('acc_finder', anonymous=True)
00068     rospy.Subscriber('odom_comb', Odometry, odom_cb)
00069     rospy.Subscriber('cmd_vel', Twist, cmd_vel_cb)
00070     rospy.loginfo('acc_finder node ready and listening. now use teleop to move your robot to the limits!')
00071     rospy.spin()
00072 
00073 
00074 if __name__ == '__main__':
00075     main()


mir_navigation
Author(s): Martin Günther
autogenerated on Wed May 8 2019 02:53:40