34 from geometry_msgs.msg
import Twist
35 from nav_msgs.msg
import Odometry
47 twist = msg.twist.twist
48 t = (rospy.Time.now() - start).to_sec()
50 if state ==
'wait_for_stop':
51 if -0.05 < twist.linear.x < 0.05
and -0.1 < twist.angular.z < 0.1:
53 rospy.loginfo(
'state transition --> %s', state)
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)
67 state =
'wait_for_stop'
68 rospy.loginfo(
'state transition --> %s', state)
74 if state !=
'stopped':
77 if msg.linear.x <= -LIN_MAX:
78 start = rospy.Time.now()
80 elif msg.linear.x >= LIN_MAX:
81 start = rospy.Time.now()
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'
92 rospy.loginfo(
'state transition --> %s', state)
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!')
103 if __name__ ==
'__main__':