| 양쪽 이전 판 이전 판 다음 판 | 이전 판 | 
| activity:public:2020:ros:201120 [2020/11/22 13:34:50]  – Youtube 링크 수정 david | activity:public:2020:ros:201120 [2021/01/28 00:38:17] (현재)  –  khr9648 | 
|---|
| ===2.1.2. package.xml=== | ===2.1.2. package.xml=== | 
| <sxh xml title:package.xml> | <sxh xml title:package.xml> | 
| <?xml version="1.0"?> | <?xml version="1.0"?>         //버전 | 
| <package> | <package> | 
| <name>ros_tutorials_topic</name> | <name>ros_tutorials_topic</name>         //이름 | 
| <version>0.1.0</version> | <version>0.1.0</version> | 
| <description>ROS turtorial package to learn the topic</description> | <description>ROS turtorial package to learn the topic</description>          //설명 | 
| <license>Apache License 2.0</license> | <license>Apache License 2.0</license> | 
| <author email="pyo@robotis.com">Yoonseok Pyo</author> | <author email="pyo@robotis.com">Yoonseok Pyo</author> | 
| <url type="website">http://www.robotis.com</url> | <url type="website">http://www.robotis.com</url> | 
| <buildtool_depend>catkin</buildtool_depend> | <buildtool_depend>catkin</buildtool_depend> | 
| <build_depend>roscpp</build_depend> | <build_depend>roscpp</build_depend>        //build할때 의존성 | 
| <build_depend>std_msgs</build_depend> | <build_depend>std_msgs</build_depend> | 
| <build_depend>message_generation</build_depend> | <build_depend>message_generation</build_depend> | 
| <run_depend>roscpp</run_depend> | <run_depend>roscpp</run_depend>        //실행 할때 의존성 | 
| <run_depend>std_msgs</run_depend> | <run_depend>std_msgs</run_depend> | 
| <run_depend>message_runtime</run_depend> | <run_depend>message_runtime</run_depend> | 
|  |  | 
| ===2.1.3. CMakeLists.txt=== | ===2.1.3. CMakeLists.txt=== | 
|  | 작성한 노드를 빌트 할때 즉 소스코드 작성 후 실행파일을 만들때 사용되는 옵션들 | 
| <sxh cpp title:CMakeLists.txt> | <sxh cpp title:CMakeLists.txt> | 
| cmake_minimum_required(VERSION 2.8.3) | cmake_minimum_required(VERSION 2.8.3) | 
| project(ros_tutorials_topic) | project(ros_tutorials_topic)           // 패키지 이름과 동일, 이름과 다르면 빌드가 안된다. | 
|  |  | 
| find_package(catkin REQUIRED COMPONENTS message_generation std_msgs roscpp) | find_package(catkin REQUIRED COMPONENTS message_generation std_msgs roscpp)           //이것이 없어야 빌드에러 없이 실행가능 catkin build안에 요구되는 구성 패키지 | 
|  |  | 
| add_message_files(FILES MsgTutorial.msg) |  | 
| generate_messages(DEPENDENCIES std_msgs) |  | 
|  |  | 
|  | add_message_files(FILES MsgTutorial.msg)           //새로 만들 메세지 이름 | 
|  | generate_messages(DEPENDENCIES std_msgs)           //의존성 | 
|  |  | 
|  | ##캐킨 패키지 옵션으로 라이브러리, 캐킨 빌드 위존성, 시스템 의존 패키지를 기술한다 | 
| catkin_package( | catkin_package( | 
| LIBRARIES ros_tutorials_topic | LIBRARIES ros_tutorials_topic | 
| include_directories(${catkin_INCLUDE_DIRS}) | include_directories(${catkin_INCLUDE_DIRS}) | 
|  |  | 
| add_executable(topic_publisher src/topic_publisher.cpp) | ##실행파일 | 
|  | add_executable(topic_publisher src/topic_publisher.cpp)           //topic_publisher:노드, topic_publisher.cpp: 노드를 만들 때 참고해야할 소스코드 | 
| add_dependencies(topic_publisher ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) | add_dependencies(topic_publisher ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) | 
| target_link_libraries(topic_publisher ${catkin_LIBRARIES}) | target_link_libraries(topic_publisher ${catkin_LIBRARIES}) | 
|  |  | 
| add_executable(topic_subscriber src/topic_subscriber.cpp) | add_executable(topic_subscriber src/topic_subscriber.cpp)           //topic_subscriber:노드, topic_subscriber.cpp: 노드를 만들 때 참고해야할 소스코드 | 
| add_dependencies(topic_subscriber ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) | add_dependencies(topic_subscriber ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) | 
| target_link_libraries(topic_subscriber ${catkin_LIBRARIES}) | target_link_libraries(topic_subscriber ${catkin_LIBRARIES}) | 
| int32 data | int32 data | 
| </sxh> | </sxh> | 
|  | time, int32 : 메세지 형식     stamp, data : 메세지 이름 | 
|  |  | 
| ====2.3. 노드 코드 작성==== | ====2.3. 노드 코드 작성==== | 
| ===2.3.1. 퍼블리셔(publisher)=== | ===2.3.1. 퍼블리셔(publisher)=== | 
| <sxh cpp title:src/topic_publisher.cpp> | <sxh cpp title:src/topic_publisher.cpp> | 
| #include "ros/ros.h"                            // ROS Default Header File | #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. | #include "ros_tutorials_topic/MsgTutorial.h"    // MsgTutorial Message File Header. The header file is automatically created when building the package. | 
|  |  | 
| // message file from the 'ros_tutorials_topic' package. The topic name is | // 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_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::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 | // 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::Rate loop_rate(10); | 
| ROS_INFO("send msg = %d", msg.stamp.nsec);  // Prints the 'stamp.nsec' 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("send msg = %d", msg.data);        // Prints the 'data' message | 
|  | //ROS INFO는 printf 와 비슷하다. ros의 경우 목적에 따라 다른 print 명령어 모양을 가지고 있다. | 
| ros_tutorial_pub.publish(msg);          // Publishes 'msg' message | ros_tutorial_pub.publish(msg);          // Publishes 'msg' message | 
|  |  | 
| // message named 'ros_tutorial_msg' is received. As an input message, | // message named 'ros_tutorial_msg' is received. As an input message, | 
| // the 'MsgTutorial' message of the 'ros_tutorials_topic' package is received. | // the 'MsgTutorial' message of the 'ros_tutorials_topic' package is received. | 
| void msgCallback(const ros_tutorials_topic::MsgTutorial::ConstPtr& msg) | 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.sec);   // Prints the 'stamp.sec' message | 
| int main(int argc, char **argv)                         // Node Main Function | int main(int argc, char **argv)                         // Node Main Function | 
| { | { | 
| ros::init(argc, argv, "topic_subscriber");            // Initializes Node Name | ros::init(argc, argv, "topic_subscriber");            // Initializes Node Name, 토픽명 | 
|  |  | 
| ros::NodeHandle nh;                                   // Node handle declaration for communication with ROS system | ros::NodeHandle nh;                                   // Node handle declaration for communication with ROS system | 
| // message file from the 'ros_tutorials_topic' package. The topic name is | // 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_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); | 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 | // A function for calling a callback function, waiting for a message to be | 
| </sxh> | </sxh> | 
|  |  | 
| =====3. 서비스(Service) 서버 <-> 클라이언트 노드===== |  | 
|  |  | 
|  |  | 
| =====4. 액션(Action) 서버 <-> 클라이언트 노드===== |  | 
|  |  | 
|  |  | 
| =====5. 파라미터===== |  | 
|  |  | 
|  |  | 
| =====6. roslaunch 활용===== |  | 
|  |  | 
|  |  |