노드는 ROS 그래프 내에서 통신하는 실행 가능한 프로세스다. 노드는 토픽을 통해 여러 정보를 문자열의 형태로 다른 노드한테 전달한다.
토픽을 통해 데이터를 주고받는 퍼블리셔와 서브스크라이버 역할을 수행하는 간단한 talker
와 listener
를 만들어 보자.
이전에 생성한 dev_ws
를 계속 사용하자.
cd ./src/
ros2 pkg create --build-type ament_cmake cpp_pubsub
dev_ws/src/cpp_pubsub/src
로 이동해 보자. 해당 디렉터리에는 CMake 패키지가 속한 디렉터리이다.
talker
예제 코드를 다음 명령어를 통해 받아 오자.
wget -O publisher_member_function.cpp https://raw.githubusercontent.com/ros2/examples/foxy/rclcpp/topics/minimal_publisher/member_function.cpp
이후 사용하는 에디터로 해당 cpp
파일을 열자.
// Copyright 2016 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <chrono>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
using namespace std::chrono_literals;
/* This example creates a subclass of Node and uses std::bind() to register a
* member function as a callback from the timer. */
class MinimalPublisher : public rclcpp::Node {
public:
MinimalPublisher() : Node("minimal_publisher"), count_(0) {
publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
timer_ = this->create_wall_timer(
500ms, std::bind(&MinimalPublisher::timer_callback, this));
}
private:
void timer_callback() {
auto message = std_msgs::msg::String();
message.data = "Hello, world! " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
publisher_->publish(message);
}
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
size_t count_;
};
int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalPublisher>());
rclcpp::shutdown();
return 0;
VSCode
기준#include "rclcpp/rclcpp.hpp"
에서 오류가 나오는 경우C/C++
확장의C/C++ Configurations
에 있는경로 포함
에 다음을 추가한다./opt/ros/foxy/**
정확한 명령어는 플랫폼과 설치 위치에 따라 달라질 수 있다.
#include <chrono>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
using namespace std::chrono_literals;
코드의 상단에는 C++
표준의 헤더 파일이 삽입되어 있고, 이후 rclcpp/rclcpp.h
헤더 파일이 삽입되어 있다.
해당 파일은 ROS 2의 가장 일반적인 기능을 사용할 수 있게 해준다.
마지막 헤더 파일 std_msgs/msg/string.hpp
데이터를 송신하기 위해 필요한 기본적인 메시지 타입을 포함하고 있다.
해당 라인 들은 노드의 의존성을 보여 주는 부분이기도 하다. 의존성은 package.xml
이나 CMakeLists.txt
를 통해 추가할 수 있다.
class MinimalPublisher : public rclcpp::Node
다음은 rclcpp::Node
를 상속 받는 노드의 클래스를 정의하는 코드이다.
클래스 내 this
는 해당 노드를 의미한다.
public:
MinimalPublisher() : Node("minimal_publisher"), count_(0) {
publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
timer_ = this->create_wall_timer(
500ms, std::bind(&MinimalPublisher::timer_callback, this));
}
클래스의 생성자에서는 count_
변수를 0
으로 초기화하고, 퍼블리셔 또한 String
타입의 메시지와 이름이 topic
인 토픽, 백업 이벤트 시 메시지를 제한하는 데 필요한 큐의 사이즈와 더불어 초기화된다. 그다음에는 timer_callback
을 1초에 2번씩 호출하는 _timer
가 초기화된다.
private:
void timer_callback() {
auto message = std_msgs::msg::String();
message.data = "Hello, world! " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
publisher_->publish(message);
}
timer_callback
함수는 메시지를 설정하고 메시지를 퍼블리싱 하는 함수이다. 매크로 함수 RCLCPP_INFO
는 퍼블리시된 모든 메시지를 콘솔에 출력해준다.
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
size_t count_;
마지막 부분은 멤버 변수들을 정의한다.
int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalPublisher>());
rclcpp::shutdown();
return 0;
}
이번엔 노드를 실제로 실행시키는 곳인 메인 함수를 보자.
rclcpp::init
함수는 ROS 2를 초기화하며, rclcpp::spin
함수는 타이머의 콜백을 포함한 노드의 데이터를 처리한다.
cd ..
dev_ws/src/cpp_pubsub
로 돌아와 package.xml
파일을 열자.
ament_cmake
빌드 툴 의존성 다음 라인에 다음을 추가하자.
<depend>rclcpp</depend>
<depend>std_msgs</depend>
find_package(ament_cmake REQUIRED)
다음 줄에 다음을 추가하자.
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
ros2 run
명령을 위한 실행 파일과 해당 이름 또한 추가하자.
ros2 run
명령이 실행 파일을 찾을 수 있도록 다음을 추가하자.
install(TARGETS
talker
DESTINATION lib/${PROJECT_NAME})
전체 코드는 다음과 같다.
cmake_minimum_required(VERSION 3.5)
project(cpp_pubsub)
# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
add_executable(talker src/publisher_member_function.cpp)
ament_target_dependencies(talker rclcpp std_msgs)
install(TARGETS
talker
DESTINATION lib/${PROJECT_NAME})
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()
이제 cpp_pubsub
패키지를 빌드 하고, 로컬 설정 파일을 소싱 한 후 실행할 수 있게 된다.
하지만 아직은 서브스크라이버 노드를 작성하지 않았기에 서브스크라이버 노드를 마저 작성하고 실행하자.
colcon build --packages-select cpp_pubsub
cd ~/dev_ws/
. install/local_setup.bash
ros2 run cpp_pubsub talker
dev_ws/src/cpp_pubsub
로 이동하자.
똑같이 예제 코드를 받아오자.
wget -O subscriber_member_function.cpp https://raw.githubusercontent.com/ros2/examples/foxy/rclcpp/topics/minimal_subscriber/member_function.cpp
ls
로 출력해 보면 다음과 같을 것이다.
publisher_member_function.cpp subscriber_member_function.cpp
// Copyright 2016 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
using std::placeholders::_1;
class MinimalSubscriber : public rclcpp::Node {
public:
MinimalSubscriber() : Node("minimal_subscriber") {
subscription_ = this->create_subscription<std_msgs::msg::String>(
"topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
}
private:
void topic_callback(const std_msgs::msg::String::SharedPtr msg) const {
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
}
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
};
int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalSubscriber>());
rclcpp::shutdown();
return 0;
}
MinimalSubscriber() : Node("minimal_subscriber") {
subscription_ = this->create_subscription<std_msgs::msg::String>(
"topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
}
서브스크라이버 코드는 퍼블리셔와 거의 비슷하다. 서브스크라이버 노드의 이름은 minimal_subscriber
이고, create_subsctiption
함수를 이용해 초기화한다. 서브스크라이버는 topic
을 통해 단순히 데이터를 수신하기 때문에 별도의 타이머는 없다.
void topic_callback(const std_msgs::msg::String::SharedPtr msg) const {
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
}
topic_callback
함수는 topic
을 통한 데이터를 받고, 매크로 함수 RCLCPP_INFO
로 콘솔에 출력해 준다.
int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalSubscriber>());
rclcpp::shutdown();
return 0;
}
메인 함수에서는 MinimalSubscriber
을 제외한 나머지는 동일하다. 의존성은 퍼블리셔와 동일하기 때문에 package.xml
을 건들 필요는 없다.
CMakeLists.txt
를 다시 열고 다음을 추가하자.
add_executable(listener src/subscriber_member_function.cpp)
ament_target_dependencies(listener rclcpp std_msgs)
install(TARGETS
talker
listener
DESTINATION lib/${PROJECT_NAME})
워크스페이스의 루트(dev_ws
)로 이동한 후 빠진 의존성이 있는지 확인해 보자.
rosdep install -i --from-path src --rosdistro foxy -y
이후 패키지를 빌드 하자.
colcon build --packages-select cpp_pubsub
새 터미널을 열고 dev_ws
에서 설정 파일을 소싱 하자.
. install/setup.bash
이제 실행하면 된다.
ros2 run cpp_pubsub talker
또 다른 새 터미널을 열고 이제는 listener
를 실행하기 위해 똑같이 반복해 주자.
. install/setup.bash
ros2 run cpp_pubsub listener