# ROS2 開始上手 這裡已預設 ROS2 已安裝好,不論使用 apt 安裝或者是 github 上的 archive 都可以,且已設置好必要的環境變數 (`setup.bash` 腳本) 這邊使用 dashing distro。 ## Create ROS2 workspace create an empty package: ``` $ ros2 pkg create --dependencies [deps] ``` 以下為具有兩個 package 的 workspace directory tree: ``` . └── src ├── ros_course_demo │ ├── CMakeLists.txt │ ├── package.xml │ └── src │ ├── listener.cpp │ └── talker.cpp └── package_name ├── CMakeLists.txt ├── package.xml └── src ├── file1.cpp └── file2.cpp ``` 不同於 ROS1 使用 `catkin` 作為 build system,ROS2 則是使用 `ament_cmake`,但是目前比較常使用另一個工具叫 `colcon` 可以同時組建 ROS1 和 ROS2 的 package,輸入 ``` $ colcon build ``` `colcon` 就會走訪 src 目錄裡的所有 package 並組建。 :::warning 為了能夠使用 `ros2 run` 執行一個 package 的執行檔,如以下命令 ``` $ ros2 run package_name executable_name ``` 必須在 CMakeLists 中為每個執行檔增加以下這一行,`${target}` 為執行檔名稱。 ``` install(TARGETS ${target} DESTINATION lib/${PROJECT_NAME}) ``` ::: ## Write a publisher and a subscriber 搭配 rclcpp example 與 rclcpp library api,便能開始使用 ROS2,參考連結均放在底下。 ### subscriber: ```c++ #include <cstdio> #include <memory> #include <string> #include <vector> #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/string.hpp" // Create a Listener class that subclasses the generic rclcpp::Node base class. // The main function below will instantiate the class as a ROS node. class Listener : public rclcpp::Node { public: Listener() : Node("listener") { auto callback = [this](const std_msgs::msg::String::SharedPtr msg) -> void { RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg->data.c_str()); }; sub_ = create_subscription<std_msgs::msg::String>("chatter", callback); } private: rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_; }; int main(int argc, char *argv[]) { rclcpp::init(argc, argv); auto node = std::make_shared<Listener>(); rclcpp::spin(node); rclcpp::shutdown(); return 0; } ``` 首先必須先建立一個 node, `class Listener` 使用繼承自 `rclcpp::Node`,並在 `Node` 的 constructor 給予這個 node 的名稱。也可以使用 `rclcpp::Node::make_shared()` 建立一個 `std::shared_ptr<rclcpp::Node>` 類型的物件。 接下來由 `rclcpp::Node::create_subscription()` 註冊 callback function,此 callback 會在呼叫 `rclcpp::spin()` 時被執行。 當無法使用 `auto` 型態宣告變數,而需要完整型態時,要使用 `rclcpp` 定義好的 `SharedPtr ` 來管理物件,以下為例 : "..." 為訂閱 topic 的資料型態。 ```c++ using rclcpp::Subscription<...>::SharedPtr = std::shared_ptr<...> ``` ### publisher: ```c++ #include <chrono> #include <cstdio> #include <memory> #include <string> #include <utility> #include <vector> #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/string.hpp" using namespace std::chrono_literals; class Talker : public rclcpp::Node { public: Talker() : Node("talker"), count_(0) { pub_ = this->create_publisher<std_msgs::msg::String>("chatter"); timerPtr_ = this->create_wall_timer(1s, [this]() { this->timerPtr_->reset(); auto message = std_msgs::msg::String(); message.data = "Hello, world! " + std::to_string(this->count_++); RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str()); this->pub_->publish(message); } ); } private: int count_; rclcpp::TimerBase::SharedPtr timerPtr_; rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_; }; int main(int argc, char *argv[]) { rclcpp::init(argc, argv); auto node = std::make_shared<Talker>(); rclcpp::spin(node); rclcpp::shutdown(); } ``` ROS2 兩個主要用來做時間管理的工具 1. **`rclcpp::WallRate`** 較容易使用,設定固定一段時間並睡眠,會跟 `while (rclcpp::ok()) ;` 一起使用 e.g. ```c++ rclcpp::WallRate loop_rate(500ms); loop_rate.sleep(); ``` 2. **`rclcpp::timer::WallTimer`** 建立一個計時器並立刻倒數。 e.g. ```c++ node = rclcpp::Node::make_shared("node_name"); auto timer_ptr = this->create_wall_timer(1s, []() { RCLCPP_INFO(node->get_logger(), "node_loop"); } ); ``` 當你建立一個 WallTimer 物件,Timer 就會開始倒數,並沒有界面可以讓你預設就是關閉,只能建立完之後呼叫 `cancel()` 或等到 `rclcpp::spin()` 之前呼叫 `reset()`。 > 註冊的 callback 在呼叫 `rclcpp::spin()` 前都不會被執行。 :::info `make_shared()` 會回傳一個 `std::shared_ptr`, ROS2 的 Timer 已經定義好 `rclcpp::TimerBase::SharedPtr` 當作 base pointer 使用來操作不同類型的 WallTimer。 ::: ### **`std::chrono`** 為何可以使用 `1s` 當作一秒帶入 `create_wall_timer()`,因為這邊使用了 C++11 的語法 **User-defined literals** > Allows integer, floating-point, character, and string literals to produce objects of user-defined type by defining a user-defined suffix. 而以下是在 C++14 `std::chrono`已經定義好的時間常數。 ```c operator""h operator""min operator""s operator""ms operator""us operator""ns ``` ```c++ constexpr std::chrono::hours operator ""h(unsigned long long h) { return std::chrono::hours(h); } ``` `std::chrono::hours` is a helper type of `std::chrono::duration` (C++14) ### demo ![](https://i.imgur.com/AnQVROq.png) ## References rclcpp example : https://github.com/ros2/examples/tree/master/rclcpp rclcpp library api : http://docs.ros2.org/dashing/api/rclcpp/ --- Todo list - [ ] Gazebo, SLAM - [ ] ROS2 QoS