2018年7月3日 星期二

ROS 2 Component

在ROS 可以將多個node 集合成一個群集nodelet,好處似乎是可以減少node 之間的通訊成本
但在ROS 2 改以component 的方式支援,目前我沒用過nodelet,所以還不確定具體差異
以下是簡單件紹component 的用法

component 與一般的node 的差異是,組成component 的元件node 不具有main function,而是會編譯成shared object 的方式(library ),由一隻稱為container 的程式載入
具ROS 官方說法是,用component 運作的node 之間的溝通效率較高

啟動component 有分三種方法

  • run-time command line:啟用ROS 2官方提供的container service,再透過指令載入node shared object
  • compile-time coding:編寫單一執行檔,將要用的node shared object link 進去
  • run-time dll open:啟用ROS 2 官方提供的執行檔,使用引數的方式代入要用的node

建立node shared object

主要是把node 的邏輯寫成一個class,初始化就放在constructor 內,而不是一個main function style 
如果是service 或者subscriber 就把要做的事情一樣放在callback 內,然後初始化就把callback function 代進去
底下程式碼是我嘗試能不能把service 與publisher 寫成同一個node 搭配component
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "std_srvs/srv/empty.hpp"
#include "visibility_control.h"
#include <chrono>
using namespace std::chrono_literals;
namespace component_demo
{
class Talker:public rclcpp::Node
{
    public:
    COMPOSITION_PUBLIC
    Talker() : Node("talker"),count_(0)
    {
        auto handler = [this](const std::shared_ptr<std_srvs::srv::Empty::Request> request, const std::shared_ptr<std_srvs::srv::Empty::Response> response) -> void
        {
            printf("receive request\n");
        };
        srv_ = create_service<std_srvs::srv::Empty>("test", handler);
        pub_ = create_publisher<std_msgs::msg::String>("chatter");
        timer_ = create_wall_timer(1s, std::bind(&Talker::on_timer, this));
    };
     
         
    protected:
    void on_timer()
    {
        auto msg = std::make_shared<std_msgs::msg::String>();
        msg->data = "Hello World: " + std::to_string(++count_);
        RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg->data.c_str())
        std::flush(std::cout);
  // Put the message into a queue to be processed by the middleware.
  // This call is non-blocking.
        pub_->publish(msg);
    };
    private:
    size_t count_;
    rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
    rclcpp::Service<std_srvs::srv::Empty>::SharedPtr srv_;
    rclcpp::TimerBase::SharedPtr timer_;
};

修改CMake

主要差異是要建library 而不是executables
cmake_minimum_required(VERSION 3.5)
project(component_demo)
# 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)
endif()
find_package(ament_cmake REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(class_loader REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rcutils REQUIRED)
find_package(rosidl_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(std_msgs REQUIRED)
find_package(std_srvs REQUIRED)
include_directories(include)
# create ament index resource which references the libraries in the binary dir
set(node_plugins "")
add_library(talker SHARED
  src/talker.cpp)
target_compile_definitions(talker
  PRIVATE "COMPOSITION_BUILDING_DLL")
ament_target_dependencies(talker
  "class_loader"
  "rclcpp"
  "std_msgs"
  "std_srvs")
rclcpp_register_node_plugins(talker "component_demo::Talker")
set(node_plugins "${node_plugins}component_demo::Talker;$<TARGET_FILE:talker>\n")
# since the package installs libraries without exporting them
# it needs to make sure that the library path is being exported
if(NOT WIN32)
  ament_environment_hooks(
    "${ament_cmake_package_templates_ENVIRONMENT_HOOK_LIBRARY_PATH}")
endif()
install(TARGETS
  talker
  ARCHIVE DESTINATION lib
  LIBRARY DESTINATION lib
  RUNTIME DESTINATION bin
  )
ament_package()

run-time command line

先開一個terminal 啟動component cotainer service
要先source setup.bash 不然會認不到自己寫的package
source install/setup.bash
ros2 run composition api_composition
#[INFO] [api_composition]: Load library /home/karlkwchen/ros2_overlay_ws/install/lib/libtalker.so
#[INFO] [api_composition]: Instantiate class component_demo::Talker
再開一個terminal 載入shared object 到service
component_demo 是我的package name
component_demo::Talker 則是namespace 底下的Talker 物件
ros2 run composition api_composition_cli component_demo component_demo::Talker
#[INFO] [api_composition_cli]: Sending request...
#[INFO] [api_composition_cli]: Waiting for response...
#[INFO] [api_composition_cli]: Result of load_node: success = true

compile-time coding

參考ROS 2 官方範例,改成載入剛剛自己建立的shared object 就行了
#include <memory>
#include "rclcpp/rclcpp.hpp"
int main(int argc, char * argv[])
{
  // Force flush of the stdout buffer.
  setvbuf(stdout, NULL, _IONBF, BUFSIZ);
  // Initialize any global resources needed by the middleware and the client library.
  // This will also parse command line arguments one day (as of Beta 1 they are not used).
  // You must call this before using any other part of the ROS system.
  // This should be called once per process.
  rclcpp::init(argc, argv);
  // Create an executor that will be responsible for execution of callbacks for a set of nodes.
  // With this version, all callbacks will be called from within this thread (the main one).
  rclcpp::executors::SingleThreadedExecutor exec;
  // Add some nodes to the executor which provide work for the executor during its "spin" function.
  // An example of available work is executing a subscription callback, or a timer callback.
  auto talker = std::make_shared<component_demo::Talker>();
  exec.add_node(talker);
  
  // spin will block until work comes in, execute work as it becomes available, and keep blocking.
  // It will only be interrupted by Ctrl-C.
  exec.spin();
  rclcpp::shutdown();
  return 0;
}

run-time dll open

啟動ROS 2 官方的node dlopen_composition,後面引數代入shared object 即可
ros2 run composition dlopen_composition `ros2 pkg prefix component_demo`/lib/libtalker.so
[INFO] [dlopen_composition]: Load library /home/karlkwchen/ros2_overlay_ws/install/lib/libtalker.so
[INFO] [dlopen_composition]: Instantiate class component_demo::Talker

NoSQL Redis intro

Redis是一個使用ANSI C編寫的開源、支援網路、基於記憶體、可選永續性的鍵值對儲存資料庫。 支援rdb 及aof 兩種儲存方式 From  https://zh.wikipedia.org/wiki/Redis Redis 目前擁有兩種資料...