ROS
Ubuntu16.04 ROS Kinetic - rviz_xycar 패키지 : RVIZ기반 자동차 바퀴 굴러가는 예제. move_joint.py
donie
2021. 1. 24. 23:27
1. 과제
RVIZ에서 자동차를 3D 형상으로 모델링하고,
핸들 조작, 바퀴를 굴릴 수 있도록 제작하는 예제.
2. rviz_xycar 패키지
catkin_create_pkg rviz_xycar rospy tf geometry_msgs urdf rviz xacro
3. xycar_motor 토픽
2021/01/15 - [ROS] - Ubuntu16.04 ROS Kinetic - xycar_motor 패키지
Ubuntu16.04 ROS Kinetic - xycar_motor 패키지
donie.tistory.com
4. launch 파일
launch폴더 만들고 xycar_3d.launch 작성.
<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="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"/> -->
<node name="move_joint" pkg="rviz_xycar" type="move_joint.py"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher"/>
</launch>
5. 소스 파일
move_joint.py 작성하고 실행권한 부여
#!/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)
rospy.init_node('move_joint')
rate = rospy.Rate(50)
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 = []
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
hello_xycar.position = [0, 0, a, b, 0, 0]
pub.publish(hello_xycar)
rate.sleep()
if __name__ == '__main__':
try:
talker()
except rospy.ROSInterruptException:
pass
6. urdf 파일
urdf 폴더를 생성하여 xycar_3d.urdf 를 작성한다.
<?xml version="1.0" ?>
<robot name="xycar" xmlns:xacro="http://www.ros.org/wiki/xacro">
<link name="base_link"/>
<link name="baseplate">
<visual>
<material name="acrylic"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.5 0.2 0.07"/>
</geometry>
</visual>
</link>
<joint name="base_link_to_baseplate" type="fixed">
<parent link="base_link"/>
<child link="baseplate"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="front_mount">
<visual>
<material name="blue"/>
<origin rpy="0 0.0 0" xyz="-0.105 0 0"/>
<geometry>
<box size="0.50 0.12 0.01"/>
</geometry>
</visual>
</link>
<joint name="baseplate_to_front_mount" type="fixed">
<parent link="baseplate"/>
<child link="front_mount"/>
<origin rpy="0 0 0" xyz="0.105 0 -0.059"/>
</joint>
<link name="front_shaft">
<visual>
<material name="black"/>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.285" radius="0.018"/>
</geometry>
</visual>
</link>
<joint name="front_mount_to_front_shaft" type="fixed">
<parent link="front_mount"/>
<child link="front_shaft"/>
<origin rpy="0 0 0" xyz="0.105 0 -0.059"/>
</joint>
<link name="rear_shaft">
<visual>
<material name="black"/>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.285" radius="0.018"/>
</geometry>
</visual>
</link>
<joint name="rear_mount_to_rear_shaft" type="fixed">
<parent link="front_mount"/>
<child link="rear_shaft"/>
<origin rpy="0 0 0" xyz="-0.305 0 -0.059"/>
</joint>
<link name="front_right_hinge">
<visual>
<material name="white"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.015"/>
</geometry>
</visual>
</link>
<joint name="front_right_hinge_joint" type="revolute">
<parent link="front_shaft"/>
<child link="front_right_hinge"/>
<origin rpy="0 0 0" xyz="0 -0.1425 0"/>
<axis xyz="0 0 1"/>
<limit effort="10" lower="-0.34"
upper="0.34" velocity="100"/>
</joint>
<link name="front_left_hinge">
<visual>
<material name="white"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.015"/>
</geometry>
</visual>
</link>
<joint name="front_left_hinge_joint" type="revolute">
<parent link="front_shaft"/>
<child link="front_left_hinge"/>
<origin rpy="0 0 0" xyz="0 0.1425 0"/>
<axis xyz="0 0 1"/>
<limit effort="10" lower="-0.34" upper="0.34" velocity="100"/>
</joint>
<link name="front_right_wheel">
<visual>
<material name="black"/>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.064" radius="0.07"/>
</geometry>
</visual>
</link>
<joint name="front_right_wheel_joint" type="continuous">
<parent link="front_right_hinge"/>
<child link="front_right_wheel"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 1 0"/>
<limit effort="10" velocity="100"/>
</joint>
<link name="front_left_wheel">
<visual>
<material name="black"/>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.064" radius="0.07"/>
</geometry>
</visual>
</link>
<joint name="front_left_wheel_joint" type="continuous">
<parent link="front_left_hinge"/>
<child link="front_left_wheel"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 1 0"/>
<limit effort="10" velocity="100"/>
</joint>
<link name="rear_right_wheel">
<visual>
<material name="black"/>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.064" radius="0.07"/>
</geometry>
</visual>
</link>
<joint name="rear_right_wheel_joint" type="continuous">
<parent link="rear_shaft"/>
<child link="rear_right_wheel"/>
<origin rpy="0 0 0" xyz="0 -0.14 0"/>
<axis xyz="0 1 0"/>
<limit effort="10" velocity="100"/>
</joint>
<link name="rear_left_wheel">
<visual>
<material name="black"/>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.064" radius="0.07"/>
</geometry>
</visual>
</link>
<joint name="rear_left_wheel_joint" type="continuous">
<parent link="rear_shaft"/>
<child link="rear_left_wheel"/>
<origin rpy="0 0 0" xyz="0 0.14 0"/>
<axis xyz="0 1 0"/>
<limit effort="10" velocity="100"/>
</joint>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="orange">
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
</material>
<material name="brown">
<color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
</material>
<material name="red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<material name="acrylic">
<color rgba="1.0 1.0 1.0 0.4"/>
</material>
</robot>
7. 실행
빌드
cm
실행
roslaunch rviz_xycar xycar_3d.launch
실행했는데 rviz에 아무것도 안나와서 당황했다.
두가지 설정
1) Fixed Frame : base_link
2) TF, RobotModel 추가
아래 예제에서도 했던 설정이다.
2021/01/20 - [ROS] - Ubuntu16.04 ROS Kinetic - ex_urdf 패키지. RVIZ 회전막대 모델
Ubuntu16.04 ROS Kinetic - ex_urdf 패키지. RVIZ 회전막대 모델
1. ex_urdf 패키지 ex_urdf 패키지 생성 catkin_create_pkg ex_urdf roscpp tf geometry_msgs urdf rviz xacro 2. urdf 파일 urdf 폴더 생성 후 pan_tilt.urdf 작성 3. launch 파일 launch..
donie.tistory.com
마지막에 종료할 때 ~/xycar_ws/src/rviz_xycar/rviz 위치에 xycar_3d.rviz로 저장하였다.