사용토픽: /xycar_motor
속력을 조절하는 구동모터와 조향각을 조절하는 조향모터를 제어
모터제어기 노드는 xycar_ws/src/xycar_device 패키지 아래 있다.
rosmsg show xycar_msgs/xycar_motor
노드 실행 후 rostopic echo /xycar_motor
: 실시간을 발행되는 토픽들의 정보를 보여줌.
구동모터범위: (후진) -50 ~ 50 (전진)
조향각 범위: (좌) -50 ~ 50 (우)
모터구동 실습코드(8_drive.py)
#! /usr/bin/env python
import rospy
import time
from xycar_msgs.msg import xycar_motor
motor_control = xycar_motor()
rospy.init_node('auto_driver')
pub = rospy.Publisher('xycar_motor', xycar_motor, queue_size=1)
def motor_pub(angle, speed):
global pub
global motor_control
motor_control.angle = angle
motor_control.speed = speed
pub.publish(motor_control)
speed = 3
while not rospy.is_shutdown():
angle = -50
for i in range(40):
motor_pub(angle, speed)
time.sleep(0.1)
angle = 0
for i in range(30):
motor_pub(angle, speed)
time.sleep(0.1)
angle = 50
for i in range(40):
motor_pub(angle, speed)
time.sleep(0.1)
angle = 0
for i in range(30):
motor_pub(angle, speed)
time.sleep(0.1)
<launch>
<!-- motor node -->
<include file="$(find xycar_motor)/launch/xycar_motor.launch"/>
<!-- auto driver -->
<node name="auto_driver" pkg="my_motor" type="8_drive.py" output="screen"/>
</launch>
/scan
/usb_cam/image_raw
/xycar_ultrasonic
/imu
/camera/depth/image_rect_raw