ROS 스터디 #4: ROS 기초 프로그래밍

2020년 11월 20일 금요일 13:30
ZOOM 화상회의

1.1.1. 표현 방식과 단위

ROS 프로그래밍은 로봇 동작을 프로그래밍하는 것인 만큼 현실 세계의 dimension에 영향을 받는다.

  1. 모든 단위는 SI단위로 사용!
  2. +x방향은 앞으로(forward), +y방향은 왼쪽으로(left), +z방향은 위로(up) 를 기준으로 함 (오른손 법칙)

1.1.2. 코드 표현 convention

ROS 프로그래밍 언어는 C++, Python 등 다양하다. 일반적으로 C++가 가장 많이 쓰인다.
C++는 Python과 달리, 줄 바꿈이나 들여쓰기가 코드에 문법적인 의미를 갖지 않는다. 따라서

catkin_create_pkg 패키지명

2.1.1. 패키지 생성

catkin_create_pkg ros_tutorials_topic

2.1.2. package.xml

<?xml version="1.0"?>         //버전
<package>
  <name>ros_tutorials_topic</name>         //이름
  <version>0.1.0</version>
  <description>ROS turtorial package to learn the topic</description>          //설명
  <license>Apache License 2.0</license>
  <author email="pyo@robotis.com">Yoonseok Pyo</author>
  <maintainer email="pyo@robotis.com">Yoonseok Pyo</maintainer>
  <url type="bugtracker">https://github.com/ROBOTIS-GIT/ros_tutorials/issues</url>
  <url type="repository">https://github.com/ROBOTIS-GIT/ros_tutorials.git</url>
  <url type="website">http://www.robotis.com</url>
  <buildtool_depend>catkin</buildtool_depend>
  <build_depend>roscpp</build_depend>        //build할때 의존성
  <build_depend>std_msgs</build_depend>
  <build_depend>message_generation</build_depend>
  <run_depend>roscpp</run_depend>        //실행 할때 의존성
  <run_depend>std_msgs</run_depend>
  <run_depend>message_runtime</run_depend>
  <export></export>
</package>

2.1.3. CMakeLists.txt

작성한 노드를 빌트 할때 즉 소스코드 작성 후 실행파일을 만들때 사용되는 옵션들

cmake_minimum_required(VERSION 2.8.3)
project(ros_tutorials_topic)           // 패키지 이름과 동일, 이름과 다르면 빌드가 안된다.

find_package(catkin REQUIRED COMPONENTS message_generation std_msgs roscpp)           //이것이 없어야 빌드에러 없이 실행가능 catkin build안에 요구되는 구성 패키지 

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})

Time stamp
int32 data
time, int32 : 메세지 형식 stamp, data : 메세지 이름

2.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;
}

2.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;
}

  • activity/public/2020/ros/201120.txt
  • 마지막으로 수정됨: 4년 전
  • 저자 khr9648