반응형

Node 는 실행가능한 프로세스다.

ROS 그래프에서 통신 할 수 있다.

 

이 예제는 토픽에서 상호간에 문자열 메세지를 건네는 것을 해본다.

노드 하나는 data publisher 가 되고 다른 하나는 subscriber 가 된다.

 

publisher 만들기!

 

일단 패키지를 만든다.

 

$ mkdir -p ~/ros2_dev_ws/src

$ cd ~/ros2_dev_ws/src

 

$ ros2 pkg create --build-type ament_cmake cpp_pubsub

이렇게 해주면

cpp_pubsub 이라는 디렉토리가 생기고, 그 안에 기본 패키지 틀이 만들어 진다.

 

$ cd ~/ros2_dev_ws/src/cpp_pubsub/src

 

만들어져 있는 예제 소스코드를 다운 받아서 쓴다.

$ wget -O publisher_member_function.cpp https://raw.githubusercontent.com/ros2/examples/master/rclcpp/topics/minimal_publisher/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 <chrono>
#include <functional>
#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp" //ros2 시스템에서 공통으로 쓰는것이라 기본으로 추가해준다고 보면 됨.
#include "std_msgs/msg/string.hpp" //publish 할때 빌트인 메세지 타입 쓰려면 추가한다.

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 //rclcpp::Node 를 상속받는다.
{
public:
  MinimalPublisher()
  : Node("minimal_publisher"), count_(0) //생성할때, count_ 를 0으로 세팅
  {
    publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10); //토픽 이름을 topic 으로 하는 String 메세지 타입을 초기화. 크기는 10
    timer_ = this->create_wall_timer(
      500ms, std::bind(&MinimalPublisher::timer_callback, this)); //1초에 두번 timer_callback 걸어줌.
  }

private:
  void timer_callback()
  {
    auto message = std_msgs::msg::String();
    message.data = "Hello, world! " + std::to_string(count_++); //count_ 값을 증가시키면서 메세지를 만듬.
    RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str()); //콘솔에 로그 찍는 매크로.
    publisher_->publish(message); //만든 메세지를 publish 한다.
  }
  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); //ROS2 초기화 시킨다.
  rclcpp::spin(std::make_shared<MinimalPublisher>()); //노드를 실행한다. 타이머 돌리고, 메세지 만들고, pub 까지 하게된다.
  rclcpp::shutdown();
  return 0;
}

Dependencies 설정

CMakeLists.txt 랑 package.xml 에다가 의존성 설정을 해야 한다.

 

package.xml 에다가 

<description> <maintainer> <license> 를 알맞게 설정해준다.

 

그리고 ament_cmake 뒤에 한줄 추가하고

 

<depend>rclcpp</depend>
<depend>std_msgs</depend>

 

이렇게 써준다. C++ 코드에서 갖다 쓴거를 추가해주는 것이다.

 

CMakeLists.txt 에다가

 

find_package(ament_cmake REQUIRED) 아랫 줄에다가

find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)

두줄 써준다.

그다음에 실행파일 이름을 talker 라고 써준다.

add_executable(talker src/publisher_member_function.cpp)
ament_target_dependencies(talker rclcpp std_msgs)

마지막으로다가 install(TARGETS 에 ros2 run 으로 실행할 수 있게 추가해준다.

install(TARGETS
  talker
  DESTINATION lib/${PROJECT_NAME})

 

Subscriber 만들기!

 

같은 패키지에서 subscriber 를 추가한다.


$ wget -O subscriber_member_function.cpp https://raw.githubusercontent.com/ros2/examples/master/rclcpp/topics/minimal_subscriber/member_function.cpp

 

#include <functional>
#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") //노드 이름 설정.
  {
	//토픽 타입은 publisher 랑 subscriber 랑 똑같게 맞춰야한다.
    subscription_ = this->create_subscription<std_msgs::msg::String>(
      "topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1)); //여기엔 타이머가 없다. topic 이 뜰때마다 응답만 해주면 된다.
  }

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[]) //main 은 완전히 같다.
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalSubscriber>());
  rclcpp::shutdown();
  return 0;
}

package.xml 은 아까 고쳐서 수정할 필요가 없다.

 

CMakeLists.txt 만 고치면 된다.

 

add_executable(listener src/subscriber_member_function.cpp)

ament_target_dependencies(listene rclcpp std_msgs)

 

두줄 추가하고

 

install 에다가 listener 추가해준다.

 

install(TARGETS
  talker
  listener <== 이거 추가
  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)

add_executable(listener src/subscriber_member_function.cpp)
ament_target_dependencies(listener rclcpp std_msgs)

install(TARGETS
    talker 
    listener 
    DESTINATION lib/${PROJECT_NAME})


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

 

Build 하기

 

빌드하기 전에 항상 dependency 체크를 해주는게 좋다. 

 

/ros2_dev_ws$ rosdep install -i --from-path src --rosdistro foxy -y
#All required rosdeps installed successfully

 

install : 필요한 dependency 있으면 깔겠다는 뜻.

-i : ignore 옵션, 뭔가 지정하면 그것을 무시한다. ROS_PACKAGE_PATH, AMENT_PREFIX_PATH 그리고 --from-path 안에 있는것을 무시한다.

--rosdistro : 명시적으로 사용하는 버전을 써준다.

-y :  뭐 물어보면 자동 yes처리.

 

이번에 만들어본 패키지만 선택해서 빌드해본다.

colcon build --packages-select cpp_pubsub

 

실행해본다.

$ . ./install/setup.bash

$ ros2 run cpp_pubsub talker 
[INFO] [1610433573.847139239] [minimal_publisher]: Publishing: 'Hello, world! 0'
[INFO] [1610433574.347119737] [minimal_publisher]: Publishing: 'Hello, world! 1'
[INFO] [1610433574.847124159] [minimal_publisher]: Publishing: 'Hello, world! 2'
[INFO] [1610433575.347016878] [minimal_publisher]: Publishing: 'Hello, world! 3'
[INFO] [1610433575.847030141] [minimal_publisher]: Publishing: 'Hello, world! 4'

 

$ ros2 run cpp_pubsub listener 
[INFO] [1610433595.347628766] [minimal_subscriber]: I heard: 'Hello, world! 43'
[INFO] [1610433595.847486153] [minimal_subscriber]: I heard: 'Hello, world! 44'
[INFO] [1610433596.347471039] [minimal_subscriber]: I heard: 'Hello, world! 45'
[INFO] [1610433596.847468899] [minimal_subscriber]: I heard: 'Hello, world! 46'
[INFO] [1610433597.347500159] [minimal_subscriber]: I heard: 'Hello, world! 47'

 

잘 된다.

반응형

'Embeded > ROS' 카테고리의 다른 글

ROS2 간단한 service 와 client 만들기 (C++)  (0) 2021.01.12
ROS2 클라이언트 라이브러리, 패키지  (0) 2021.01.11
ROS 1 연습  (0) 2021.01.04
Posted by Real_G