5 from geometry_msgs.msg
import Twist
6 from nav_msgs.msg
import Odometry
18 twist = msg.twist.twist
19 t = (rospy.Time.now() - start).to_sec()
21 if state ==
'wait_for_stop':
22 if -0.05 < twist.linear.x < 0.05
and -0.1 < twist.angular.z < 0.1:
24 rospy.loginfo(
'state transition --> %s', state)
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)
38 state =
'wait_for_stop' 39 rospy.loginfo(
'state transition --> %s', state)
45 if state !=
'stopped':
48 if msg.linear.x <= -LIN_MAX:
49 start = rospy.Time.now()
51 elif msg.linear.x >= LIN_MAX:
52 start = rospy.Time.now()
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' 63 rospy.loginfo(
'state transition --> %s', state)
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!')
74 if __name__ ==
'__main__':