학습 내용
RVIZ 기반 3D 자동차 제어프로그래밍
이번 실습의 주제는 RVIZ에서 3D 자동차를 8 자 주행시켜 보는 것이다. RVIZ는 ROS에서 사용되는 3차원 시각화 도구이며 일반적으로 ROS를 설치할 때 ros-kinetic-desktop-full 명령어에 포함되어 설치된다. RVIZ를 실행하기 위해서 roscore 명령으로 마스터 노드를 실행시킨 후 터미널에 rviz 명령어를 작성하면 된다.
$ rviz // 혹은 rosrun rvis rvis
주행하기 전에 먼저 바퀴가 정확히 원하는 대로 동작하는지 확인하는 실습을 해보자. rviz_xycar 패키지를 생성하고 코드를 작성하여 RVIZ를 통해 자동차 바퀴의 동작을 확인한다(*xycar_motor 패키지는 외부 공개 불가인 점 양해부탁드립니다). 패키지 내부에 rviz_drive.rviz와 rviz_drive.launch를 작성하고 동작을 위한 converter.cpp와 rviz_8_drive.cpp 코드를 작성한다.
전체 디렉토리 구성은 다음과 같다.
xycar_ws
├─ build
├─ devel
└─ src
└─ rviz_xycar (new!)
├─ urdf
├─ rviz
| └─ rviz_drive.rviz (new!)
├─ launch
| └─ rviz_drive.launch (new!)
└─ src
├─ converter.cpp (new!)
└─ rviz_8_drive.cpp (new!)
rviz_8_drive.cpp는 지난 실습의 8_drive.cpp와 비슷하게 작성하면 된다. 이때 xycar_motor의 토픽을 받아오기 위해 CMakeLists.txt를 아래와 같이 수정해야 한다.
find_package(catkin REQUIRED COMPONENTS
...
xycar_motor // 받아오려는 패키지를 추가한다
)
## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES // 활성화
geometry_msgs
)
include_directories(
include
${catkin_INCLUDE_DIRS}
${CMAKE_CURRENT_SOURCE_DIR}/../../xycar_motor/msg // xycar_motor.msg가 있는 경로
)
다음으로 converter.cpp를 작성하여 converter 노드가 명령을 받아 포맷을 변경한 후 RVIZ로 전송하도록 구현한다. 아래 사진은 모터제어 토픽의 전송 과정을 나타낸 것이다.
converter.cpp의 역할은 xycar_motor 토픽을 받아 이를 RVIZ가 읽을 수 있는 형태로 변환하고 joint_states 토픽으로 발행하는 것이다.
#include "ros/ros.h"
#include "xycar_motor/xycar_motor.h"
#include "sensor_msgs/JointState.h"
#include "std_msgs/Header.h"
#include <cmath>
#define _USE_MATH_DEFINES
ros::Publisher pub;
sensor_msgs::JointState msg_joint_states;
double l_wheel = -3.14;
double r_wheel = -3.14;
void callback(const xycar_motor::xycar_motor::ConstPtr& data) {
double Angle = data->angle;
double steering = M_PI * Angle * 0.4 / 180.0;
if (l_wheel > 3.14) {
l_wheel = -3.14;
r_wheel = -3.14;
} else {
l_wheel += 0.01;
r_wheel += 0.01;
}
msg_joint_states.header.stamp = ros::Time::now(); // Set timestamp to current time
msg_joint_states.position = {steering, steering, r_wheel, l_wheel, r_wheel, l_wheel};
pub.publish(msg_joint_states);
}
int main(int argc, char** argv) {
ros::init(argc, argv, "converter");
ros::NodeHandle nh;
pub = nh.advertise<sensor_msgs::JointState>("joint_states", 10);
msg_joint_states.header = std_msgs::Header();
msg_joint_states.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"};
msg_joint_states.velocity = {};
msg_joint_states.effort = {};
ros::Subscriber sub = nh.subscribe("xycar_motor", 1, callback);
ros::spin();
return 0;
}
rviz_drive.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/rviz_drive.rviz"/>
<node name="robot_state_publisher" pkg="robot_state_publisher"
type="state_publisher"/>
<node name="driver" pkg="rviz_xycar" type="rviz_8_drive" />
<node name="converter" pkg="rviz_xycar" type="converter" />
</launch>
이제 roslaunch 명령어로 동작을 확인하자. 또한 rqt_graph로 노드와 토픽의 구성을 살펴보고 rosrun tf view_frames 명령으로 트리가 제대로 구성이 되었는지 확인하자.
$ roslaunch rviz_xycar rviz_drive.launch
$ rqt_graph
$ rosrun tf view_frames
RVIZ 화면의 결과와 rqt_graph, tree 출력은 다음과 같다.
화면에 출력되는 자동차 바퀴의 움직임을 보면 원하는 대로 바퀴가 동작하는 것을 알 수 있다. 또한 제대로 노드와 토픽이 구성되어 있는지 확인하고 TF프레임을 통해 부모와 자식 관계가 제대로 구성이 된 것을 확인할 수 있다.
추가로 rostopic echo /topic 명령을 통해 토픽의 내용을 확인하여 정확히 변환되어 전달되고 있는지도 확인할 수 있다.
결론
이번 실습에서는 RVIZ 기반 3D 자동차 제어프로그래밍에 대해 학습하였다. 실제 8 자 주행전 자동차의 바퀴가 정확히 원하는 동작을 수행하는 지 확인하는 과정을 통해 제어시스템 내부에서 토픽이 전송되어 동작하는 전체 흐름을 알 수 있었고 다양한 시각화 명령어를 통해 수치적으로 분석하고 디버깅하는 법을 배울 수 있었다. 이 다음으로는 Odometry에 대해 학습하고 이를 활용하여 8자 주행하는 자동차제어시스템을 실습해 볼 것이다.
'Study > ROS' 카테고리의 다른 글
[ROS 튜토리얼] 라이다 센서를 위한 ROS 노드와 토픽 (0) | 2023.10.09 |
---|---|
[ROS 튜토리얼] RVIZ Ordometry 활용 및 3D 자동차 주행프로그래밍 (1) | 2023.10.08 |
[ROS 튜토리얼] 모터제어기 ROS 프로그래밍 (0) | 2023.10.06 |
[ROS 튜토리얼] 과제 #5. 협업해야 하는 노드를 순서대로 기동 시킬 수 있는가? (1) | 2023.10.04 |
[ROS 튜토리얼] 과제 #4. 주기적 발송에서 타임슬롯을 오버하면 어떻게 되는가? (0) | 2023.10.04 |