[ROS 2] C++ Publisher ๋ง๋ค๊ธฐ
ROS 2์์ C++ ๊ธฐ๋ฐ publisher๋ฅผ ๋ง๋ค์ด๋ณด์!
์ ์ฒด ์ฝ๋
#include <chrono>
#include <functional>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
using namespace std::chrono_literals;
class MyPublisher : public rclcpp::Node
{
public:
MyPublisher() : Node("my_publisher"), count_(0)
{
pub_ = this->create_publisher<std_msgs::msg::String>("msg", 10);
timer_ = this->create_wall_timer(500ms, std::bind(&MyPublisher::timerCallback, this));
}
private:
void timerCallback()
{
auto msg = std_msgs::msg::String();
msg.data = "bigbigpark! " + std::to_string(count_);
RCLCPP_INFO(this->get_logger(), "Publish: %s", msg.data.c_str());
pub_->publish(msg);
}
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
size_t count_;
};
int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MyPublisher>());
rclcpp::shutdown();
return 0;
}
์ฝ๋๊ฐ ์ข ROS 1๊ณผ๋ ๋น์ทํ ๋ฏ ๋ค๋ฅด๋ค ?
์ฝ๋ ๋ถ์
#include <chrono>
#include <functional>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
using namespace std::chrono_literals;
์๊ฐ ๊ด๋ จ ํจ์ ๋ผ์ด๋ธ๋ฌ๋ฆฌ์ธ chrono
๋ฉ๋ชจ๋ฆฌ ๋์ ๋ฐฐ์ด ํ ๋น ๊ด๋ จ memory
ํจ์๋ฅผ ๊ฐ์ฒด์ฒ๋ผ! functional
์์ผ๋ก ์ฝ๋๋ฅผ ์์ฑํ ๋๋ ๋ญ๊ฐ ํ์์ธ ๊ฒ ๊ฐ์์.. ์ผ๋จ ์ต๊ด์ ์ผ๋ก ์์ฑํ๊ธฐ๋ก ํ๋ค
์ด์ ๋ ros/ros.h๊ฐ ์๋ rclcpp/rclcpp.hpp๋ก ๋ฐ๋๋ฏ ํ๋ค
๋ํ ๋ฉ์ธ์ง ํจํค์ง๋ฅผ ์ฝ์ด์ฌ ๋๋ std_msgs/String.h์์ std_msgs/msg/string.hpp๋ก ๋ณ๊ฒฝ๋์๋ค
๊ทผ๋ฐ.. ROS 2 ํ๋ฐ์ฌ๋ ์ฑ ๋ณด๋ฉด ํค๋ํ์ผ์ ๋ค์ด๋ฐ ๊ท์น์ ์ด๊ธ๋๋ ๊ฒ์ด ์๋๊ฐ..??
๊ทธ๋ฆฌ๊ณ std::chrono_literals๋ ์๊ฐ์ ์ฝ๊ฒ ๋ํ๋ด๊ธฐ ์ํ ๋ค์์คํ์ด์ค๋ค
๋ค์์คํ์ด์ค๋ ๊ถ์ฅํ์ง ์๋๋ฐ..ใ
class MyPublisher : public rclcpp::Node
{
public:
MyPublisher() : Node("my_publisher"), count_(0)
{
pub_ = this->create_publisher<std_msgs::msg::String>("msg", 10);
timer_ = this->create_wall_timer(500ms, std::bind(&MyPublisher::timerCallback, this));
}
private:
void timerCallback()
{
auto msg = std_msgs::msg::String();
msg.data = "bigbigpark! " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Publish: %s", msg.data.c_str());
pub_->publish(msg);
}
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
size_t count_;
};
ROS 1 ๊ฐ์์๋ ๋ฐ๋ก ํด๋์ค๋ฅผ ์ด์ฉํด์ ์ค๋ช
ํ์ง ์์๋๋ฐ, ์ด ROS 2๋ ์๋ฌด๋๋ C++์ ๋ํ ์ ๋ฐ์ ์ธ ์ง์์ด ์๋ ์ฌ๋์ ํ๊ฒ์ผ๋ก ๋ง๋ค์ด์ก๋ค
๊ทธ๋ฆฌ๊ณ rclcpp::Node ๋ผ๋ ํด๋์ค๋ฅผ ์์ํ๋ ๊ฒ์ ์ ์ ์๋ค
ํนํ ํด๋์ค ์์ฑ์์์ ๋
ธ๋ ์ด๋ฆ์ ์ธ์๋ก ๋ฐ์์ ๋ฐ๋ก ์ ์ธํ๋ ๋ถ๋ถ์ ๊ธฐ์ตํด์ฃผ์
๋ํ ROS 1์ ์์๋ ros::NodeHandle์ด ์์ด์ง๊ณ this->create_publisher๋ก ๋ณ๊ฒฝ์ด ๋์๋ค
ROS 1์์๋ main ๋ฌธ ์์์ while ๋ฌธ์ ๋๋ฆฌ๋ฉด์ publish๋ฅผ ํ๋ค๋ฉด, ROS 2์์๋ timer๋ผ๋ ๊ฒ์ ์ด์ฉํ์ฌ publish ์ฝ๋๋ฅผ ์งค ๋ callback ํจ์๋ฅผ ๋๋ฆฐ๋ค
์ฆ, ๋์ฑ ์ ํํ ์๊ฐ์ publishํ๊ฒ ๋ค๋ ์๋ฏธ๋ค. ๋ฐ๋ผ์ ์ ์ฝ๋๋ 500ms ๋ง๋ค ํ์ด๋จธ๋ฅผ ์์ ํ๋๋ฐ, ๊ทธ ๋๋ง๋ค count๋ฅผ ์ฆ๊ฐ์ํค๋ฉด์ ๋ฉ์ธ์ง๋ฅผ publishํ๋ค๋ ๋ป์ด ๋๋ค
private:
void timerCallback()
{
auto msg = std_msgs::msg::String();
msg.data = "bigbigpark! " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Publish: %s", msg.data.c_str());
pub_->publish(msg);
}
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
size_t count_;
์ด ๋ถ๋ถ์ callback ํจ์์ด๊ธด ํ๋ฐ, ROS_INFO ์์ RCLCPP_INFO๋ก ๋ณ๊ฒฝ๋์๋ค
๋ํ this->get_logger()๋ฅผ ์ ๊ณตํ๋ฉด์, ๋ก๊น
์ ๋ํด์๋ ๊ฐ์ ์ด ์ด๋ฃจ์ด์ง ๊ฒ์ ๋ณผ ์ ์๋ค
๊ทธ๋ฆฌ๊ณ ํ์ด๋จธ ๋ณ์์ ํผ๋ธ๋ฆฌ์ ๋ณ์๊ฐ ๋ชจ๋ sharedPtr์ธ ์ค๋งํธํฌ์ธํฐ๋ก ์ ์ธ์ด ๋์ด์๋ค
int main(int argc, char** argv)
{
// ROS 2๋ฅผ initialize ํ๊ฒ ๋ค
rclcpp::init(argc, argv);
// ํ์ด๋จธ ์ฝ๋ฐฑ์ ์ด์ฉํ์ฌ ๋
ธ๋๋ก๋ถํฐ ๋ฐ์ดํฐ๋ฅผ ์ฒ๋ฆฌํ๊ฒ ๋ค
rclcpp::spin(std::make_shared<MyPublisher>());
rclcpp::shutdown();
return 0;
}
๋๋ main๋ฌธ์ ์ฒ์์ ๋ณด๊ณ publisher์ธ๋ฐ ์ spin์ด ์์ง ๊ถ๊ธ์ฆ์ ๊ฐ์ก๋ค
์ฌ์ค ์์ด๋ ๋์ง๋ง ์ ํํ ์๊ฐ์ผ๋ก publish ํ๊ธฐ ์ํด์๋ ์์ฒด timer๋ฅผ ์ด์ฉํ๋ ๊ฒ์ด ์ข์ผ๋ฉฐ, ์ ๋ ๊ฒ ํด๋์ค๋ฅผ ์ ์ธํ ๋๋ ์ค๋งํธํฌ์ธํฐ๋ก ์ ์ธํ๋ ๊ฒ์ ์ ์ ์๋ค
package.xml ์์
ํ์ผ์ ์ด์ด์ buildtool_depend์ ament_cmake๋ผ๊ณ ์ ํ ์๋ ์ค ๋ฐ๋ก ๋ฐ์๋ค๊ฐ ๋ค์์ ์ถ๊ฐํด์ค๋ค
<depend>rclcpp</depend>
<depend>std_msgs</depend>
์ด์ ์ด ์์กด์ฑ์ CMakeLists.txt์ ๋ฐ์ํ๋ฉด ๋๋ค
CMakeLists.txt ์์
ํ์ผ์ ์ด์ด์ find_package(ament_cmake REQUIRED) ๋ค์ ์ค์ ์ด๋ ๊ฒ ์ถ๊ฐํด์ค๋ค
์ด ํ๋ก์ ํธ์ dependencies๋ฅผ ์ถ๊ฐํด์ฃผ๋ ๊ณผ์ ์ด๋ค
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
๋ค์์ ์์ค์ฝ๋๋ฅผ ๊ธฐ๋ฐ์ผ๋ก ์คํํ์ผ์ ๋ง๋๋ ์ ์ฐจ๋ค
add_executable(pub src/pub.cpp)
ament_target_dependencies(pub rclcpp std_msgs)
์ด ์คํํ์ผ ๋ช
์ ros 2๊ฐ ์ฐพ์ ์ ์๋๋ก ํด์ฃผ์
install(TARGETS
pub
DESTINATION lib/${PROJECT_NAME})
๋น๋ ๋ฐ ์คํ
๋ฐ์ ์ฌ์ฉ๋๋ ๋จ์ถ์ด๋ ์ฌ๊ธฐ๋ฅผ ์ฐธ์กฐํ์
์๋์ ๊ฐ์ด ํจํค์ง ๋น๋ ํ์ ์คํํด๋ณธ๋ค
$ cbp my_ros2
$ ros2 run my_ros2 pub
์๋์ ๊ฐ์ด ์ถ๋ ฅ๋๋ค๋ฉด ์ฑ๊ณต!
[INFO] [1662093558.003252577] [my_publisher]: Publish: bigbigpark! 0
[INFO] [1662093558.503316640] [my_publisher]: Publish: bigbigpark! 1
[INFO] [1662093559.003363595] [my_publisher]: Publish: bigbigpark! 2
[INFO] [1662093559.503298140] [my_publisher]: Publish: bigbigpark! 3
[INFO] [1662093560.003335839] [my_publisher]: Publish: bigbigpark! 4
[INFO] [1662093560.503317732] [my_publisher]: Publish: bigbigpark! 5
[INFO] [1662093561.003289612] [my_publisher]: Publish: bigbigpark! 6
[INFO] [1662093561.503353750] [my_publisher]: Publish: bigbigpark! 7
[INFO] [1662093562.003375748] [my_publisher]: Publish: bigbigpark! 8
[INFO] [1662093562.503328776] [my_publisher]: Publish: bigbigpark! 9
[INFO] [1662093563.003220890] [my_publisher]: Publish: bigbigpark! 10
Leave a comment