ROS STUDY #4 : ROS 기초프로그래밍(topic 퍼블리시)
1. topic, service, action의 개념
1.1 메시지 통신의 종류
1.2 Topic이란?
토픽은 실시간으로 전송되는 메시지이다. 단방향성을 갖고 있다. 퍼블리셔나 서브스크라이버가 중지하지 않는 이상, 메시지를 계속 보낸다. 이러한 특성 때문에 로봇의 상태나 센서 메시지 등을 보낼 때 토픽을 많이 사용한다.
1.3 Service란?
서비스는 1회성의 메시지이다. 토픽에서는 동등한 지위의 두 개의 노드간에 통신이 이루어졌지만, 서비스는 서비스 서버와 클라이언트 사이에서 통신이 이루어진다. 서비스 클라이언트는 서비스를 요청하는 입장이고, 서비스 서버는 서비스를 요청받아 정해진 프로세스를 수행하고 응답하는 역할이다. 요청과 응답을 수행하면, 서로의 접속을 끊으므로, 다시 필요하면 접속부터 새롭게 진행해야 한다. 1회성이라는 특징때문에, 로봇에 1회성 행동 명령을 내려야 하는 경우 많이 사용된다.
1.4 Action이란?
액션은 서비스에서 중간 결과값을 보고하는 부분이 추가된 통신이다. 서비스를 기반으로 만들어진 통신이라 생각하기 쉽지만, 실제로는 토픽을 바탕으로 구동된다. 그렇기 때문에 rostopic list라는 명령어 사용시, 액션에서 사용하는 goal, status, cancel, result, feedback의 5개 토픽을 확인할 수 있다. 서비스와는 다르게 클라이언트에서 취소명령을 보내거나, 서버에서 결과값을 보내면 접속이 종료된다.
위의 사진들은 <ROS로봇프로그래밍>을 참조했습니다.
2. 패키지 내부 살펴보기
파일 | 설명 |
---|---|
/include | 패키지 실행에 필요한 헤더 파일 존재 |
/launch | ROS 노드를 실행하기 위한 실행 파일 존재 |
/rviz | RViz 데이터 값의 결과 구성을 저장 |
/src | 코드 소스 파일 존재 |
CMakeLists.txt | 빌드 설정 파일 |
package.xml | 패키지 설정 파일 |
3. topic 퍼블리시
3.1. 패키지 기본 설정
3.1.1. 패키지 생성
catkin_create_pkg ros_tutorials_topic message_generation roscpp std_msgs catkin_create_pkg [만들 패키지 이름] [의존성 패키지1] [의존성 패키지2]...catkin_ws로 이동 후, 터미널에서 위의 명령어 입력
3.1.2. package.xml
<package format="2"> ## 패키지 형식 <name>ros_tutorials_topic</name> ## 패키지 이름 <version>0.0.0</version> ## 패키지 버전(나중에 배포할 시 업데이트 하며 수정하면 됨) <description>The ros_tutorials_topic package</description> ## 패키지 설명 <maintainer email="kdh@todo.todo">kdh</maintainer> ## 패키지를 유지, 보수 하는 사람의 연락처 <license>TODO</license> ## 라이센스 입력하는 곳(Apach 2.0, BSD 등) <buildtool_depend>catkin</buildtool_depend> ##패키지를 빌드하는 데 사용되는 툴 ##빌드시 사용되는 의존성 패키지 <build_depend>message_generation</build_depend> <build_depend>roscpp</build_depend> <build_depend>std_msgs</build_depend> ##실행파일 빌드시 사용되는 의존성 패키지(src폴더의 파일들이 노드 실행파일로 만들어질 때 사용되는 패키지) <build_export_depend>roscpp</build_export_depend> <build_export_depend>std_msgs</build_export_depend> ##빌드 후 실행시 사용되는 의존성 패키지 <exec_depend>roscpp</exec_depend> <exec_depend>std_msgs</exec_depend> <exec_depend>message_runtime</exec_depend> <export> </export> </package>
3.1.3. CMakeLists.txt
작성한 노드를 빌트 할때 즉 소스코드 작성 후 실행파일을 만들때 사용되는 옵션들
cmake_minimum_required(VERSION 2.8.3) ##cmake의 최소 요구 버전 project(ros_tutorials_topic) ## 패키지 이름과 동일, 이름과 다르면 빌드가 안된다. find_package(catkin REQUIRED COMPONENTS message_generation std_msgs roscpp) ##의존성 패키지 add_message_files(FILES MsgTutorial.msg) ##새로 만들 메세지 이름 generate_messages(DEPENDENCIES std_msgs) ##의존성 ##캐킨 패키지 옵션으로 라이브러리, 캐킨 빌드 위존성, 시스템 의존 패키지를 기술한다 catkin_package( LIBRARIES ros_tutorials_topic CATKIN_DEPENDS std_msgs roscpp ) include_directories(${catkin_INCLUDE_DIRS}) ##실행파일 add_executable(topic_publisher src/topic_publisher.cpp) ##topic_publisher:노드, topic_publisher.cpp: 노드를 만들 때 참고해야할 소스코드 add_dependencies(topic_publisher ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) target_link_libraries(topic_publisher ${catkin_LIBRARIES}) add_executable(topic_subscriber src/topic_subscriber.cpp) ##topic_subscriber:노드, topic_subscriber.cpp: 노드를 만들 때 참고해야할 소스코드 add_dependencies(topic_subscriber ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) target_link_libraries(topic_subscriber ${catkin_LIBRARIES})
3.2. 메세지(msg) 등록
time stamp int32 datatime, int32 : 메세지 형식 stamp, data : 메세지 이름
3.3. 노드 코드 작성
3.3.1. 퍼블리셔(publisher)
#include "ros/ros.h" // ROS Default Header File, 밑의 ros::init~~, ros::NodeHandle nh; 등등을 사용가능하게 함 #include "ros_tutorials_topic/MsgTutorial.h" // MsgTutorial Message File Header. The header file is automatically created when building the package. int main(int argc, char **argv) // Node Main Function { ros::init(argc, argv, "topic_publisher"); // Initializes Node Name ros::NodeHandle nh; // Node handle declaration for communication with ROS system // Declare publisher, create publisher 'ros_tutorial_pub' using the 'MsgTutorial' // message file from the 'ros_tutorials_topic' package. The topic name is // 'ros_tutorial_msg' and the size of the publisher queue is set to 100. ros::Publisher ros_tutorial_pub = nh.advertise<ros_tutorials_topic::MsgTutorial>("ros_tutorial_msg", 100); //ros_tutorial_msg:토픽의 이름, 네트워크가 늦을때 큐사이즈 100개 쌓아 놓고 보냄. 지연되는것을 늦출수 있음. // Set the loop period. '10' refers to 10 Hz and the main loop repeats at 0.1 second intervals ros::Rate loop_rate(10); ros_tutorials_topic::MsgTutorial msg; // Declares message 'msg' in 'MsgTutorial' message file format int count = 0; // Variable to be used in message while (ros::ok()) { msg.stamp = ros::Time::now(); // Save current time in the stamp of 'msg' msg.data = count; // Save the the 'count' value in the data of 'msg' ROS_INFO("send msg = %d", msg.stamp.sec); // Prints the 'stamp.sec' message ROS_INFO("send msg = %d", msg.stamp.nsec); // Prints the 'stamp.nsec' message ROS_INFO("send msg = %d", msg.data); // Prints the 'data' message //ROS INFO는 printf 와 비슷하다. ros의 경우 목적에 따라 다른 print 명령어 모양을 가지고 있다. ros_tutorial_pub.publish(msg); // Publishes 'msg' message loop_rate.sleep(); // Goes to sleep according to the loop rate defined above. ++count; // Increase count variable by one } return 0; }
3.3.2. 서브스크라이버(subscriber)
#include "ros/ros.h" // ROS Default Header File #include "ros_tutorials_topic/MsgTutorial.h" // MsgTutorial Message File Header. The header file is automatically created when building the package. // Message callback function. This is a function is called when a topic // message named 'ros_tutorial_msg' is received. As an input message, // the 'MsgTutorial' message of the 'ros_tutorials_topic' package is received. void msgCallback(const ros_tutorials_topic::MsgTutorial::ConstPtr& msg) //메세지 형태 { ROS_INFO("recieve msg = %d", msg->stamp.sec); // Prints the 'stamp.sec' message ROS_INFO("recieve msg = %d", msg->stamp.nsec); // Prints the 'stamp.nsec' message ROS_INFO("recieve msg = %d", msg->data); // Prints the 'data' message } int main(int argc, char **argv) // Node Main Function { ros::init(argc, argv, "topic_subscriber"); // Initializes Node Name, 토픽명 ros::NodeHandle nh; // Node handle declaration for communication with ROS system // Declares subscriber. Create subscriber 'ros_tutorial_sub' using the 'MsgTutorial' // message file from the 'ros_tutorials_topic' package. The topic name is // 'ros_tutorial_msg' and the size of the publisher queue is set to 100. ros::Subscriber ros_tutorial_sub = nh.subscribe("ros_tutorial_msg", 100, msgCallback); // 그 메세지를 받았을때 실행하는 callback함수 // A function for calling a callback function, waiting for a message to be // received, and executing a callback function when it is received. ros::spin(); return 0; }