6 from geometry_msgs.msg
import Twist
7 from ackermann_msgs.msg
import AckermannDriveStamped
11 if omega == 0
or v == 0:
15 return math.atan(wheelbase / radius)
20 global ackermann_cmd_topic
23 global cmd_angle_instead_rotvel
28 if cmd_angle_instead_rotvel:
29 steering = data.angular.z
33 msg = AckermannDriveStamped()
34 msg.header.stamp = rospy.Time.now()
35 msg.header.frame_id = frame_id
36 msg.drive.steering_angle = steering
45 if __name__ ==
'__main__':
48 rospy.init_node(
'cmd_vel_to_ackermann_drive')
50 twist_cmd_topic = rospy.get_param(
'~twist_cmd_topic',
'/cmd_vel')
51 ackermann_cmd_topic = rospy.get_param(
'~ackermann_cmd_topic',
'/ackermann_cmd')
52 wheelbase = rospy.get_param(
'~wheelbase', 1.0)
53 frame_id = rospy.get_param(
'~frame_id',
'odom')
54 cmd_angle_instead_rotvel = rospy.get_param(
'/move_base/TebLocalPlannerROS/cmd_angle_instead_rotvel',
False)
56 rospy.Subscriber(twist_cmd_topic, Twist, cmd_callback, queue_size=1)
57 pub = rospy.Publisher(ackermann_cmd_topic, AckermannDriveStamped, queue_size=1)
59 rospy.loginfo(
"Node 'cmd_vel_to_ackermann_drive' started.\nListening to %s, publishing to %s. Frame id: %s, wheelbase: %f",
"/cmd_vel", ackermann_cmd_topic, frame_id, wheelbase)
63 except rospy.ROSInterruptException:
def convert_trans_rot_vel_to_steering_angle(v, omega, wheelbase)