roslaunch rviz_xycar xycar_3d.launch
실행된 RVIZ
Joint_state_publisher UI
수동으로 xycar의 제원을 조작할 수 있다.
rqt_graph
명령어를 통해 /joint_states
토픽이 발행되는 것을 볼 수 있다.
RVIZ 뷰어가 받는 토픽 확인하기
# RVIZ 내부에서 주고받는 토픽을 알아 보자
rostopic info joint_states
sensor_msgs/JointState
라는 타입의 토픽을 주고 받고 있음을 알 수 있다.
# 그러면 sensor_msgs/JointState는 어떤 내용을 포함하고 있을까?
rosmsg show sensor_msgs/JointState
sensor_msgs/JointState
가 주고 받는 토픽의 구조는 이렇다.
# 토픽 정보를 직접 받아와 읽어 보자.
rostopic echo joint_states
header
도 보이고,
name
은 Joint_state_publisher UI
에서 봤던 이름들이 있다.
position
은 각각의 회전 정보를 알려주는 것 같다.
rviz_xycar
move_joint.launch
move_joint.py
<launch>
<param name="robot_description" textfile="$(find rviz_xycar)/urdf/xycar_3d.urdf"/>
<param name="use_gui" value="true"/>
<!-- rviz display -->
<node name="rviz_visualizer" pkg="rviz" type="rviz" required="true"
args="-d $(find rviz_xycar)/rviz/xycar_3d.rviz"/>
<node name="robot_state_publisher" pkg="robot_state_publisher"
type="state_publisher"/>
# move_joint.py 코드를 통해 RVIZ를 제어하기 위한 노드 생성
<node name= "move_joint" pkg="rviz_xycar" type= "move_joint.py" />
</launch>
#!/usr/bin/env python
import rospy
from sensor_msgs.msg import JointState
from std_msgs.msg import Header
def talker():
pub = rospy.Publisher('joint_states', JointState, queue_size=10)
# node 이름은 move_joint, 위 move_joint.launch 파일 참조
rospy.init_node('move_joint')
rate = rospy.Rate(50) # 50Hz로 동작
# 토픽 내용 채워 넣기
# rosmsg show sensor_msgs/JointState 에서 확인할 수 있음
hello_xycar = JointState()
hello_xycar.header = Header()
hello_xycar.name = ['front_right_hinge_joint', 'front_left_hinge_joint',
'front_right_wheel_joint', 'front_left_wheel_joint',
'rear_right_wheel_joint','rear_left_wheel_joint']
hello_xycar.velocity = []
hello_xycar.effort = []
# 초기값, 단위는 라디안 (3.14라디안 = 180도)
a = -3.14
b = -3.14
while not rospy.is_shutdown():
hello_xycar.header.stamp = rospy.Time.now()
# 바퀴가 굴러가는 코드
if a >= 3.14:
a = -3.14
b = -3.14
else:
a += 0.01
b += 0.01
# front_right_wheel_joint, front_left_wheel_joint 자리.
# 앞바퀴 2개를 회전시키겠다 라는 뜻
hello_xycar.position = [0, 0, a, b, 0, 0]
pub.publish(hello_xycar)
rate.sleep()
if __name__ == '__main__':
try:
talker()
except rospy.ROSInterruptException:
pass
move_joint.py
실행 권한 부여
chmod +x move_joint.py
패키지 빌드
cm
잘 움직인다.