1
0

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?

More than 1 year has passed since last update.

ROS2における独自QoSプロファイルの設定方法

Last updated at Posted at 2022-12-13

ROS2 独自QoSプロファイル設定について

ROS2には、既にいくつかQoSプロファイルが用意されています。
ただ自分専用のプロファイルを作りたいと思って、実装してみたのでメモ程度にここに残しておきます。
ROS2で用意されているプロファイルの一覧も置いておきます。
プログラムはROS2 DocumentationのWriting a simple publisher and subscriber(C++)を改良したものです。

ソースコード

#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")
    {
      custom_qos_profile.depth = 10;
      custom_qos_profile.history = rmw_qos_history_policy_t::RMW_QOS_POLICY_HISTORY_KEEP_LAST;
      custom_qos_profile.reliability = rmw_qos_reliability_policy_t::RMW_QOS_POLICY_RELIABILITY_RELIABLE;
      custom_qos_profile.durability = rmw_qos_durability_policy_t::RMW_QOS_POLICY_DURABILITY_VOLATILE;
      rclcpp::QoS qos_profile(rclcpp::KeepLast(10), custom_qos_profile);
      subscription_ = this->create_subscription<std_msgs::msg::String>(
      "topic", qos_profile, std::bind(&MinimalSubscriber::topic_callback, this, _1));
    }

  private:
    void topic_callback(const std_msgs::msg::String::SharedPtr msg)
    {
      RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
    }
    rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
    rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalSubscriber>());
  rclcpp::shutdown();
  return 0;
}

それぞれのパラメータについては、rmw_qos_profile_t Struct Referenceを参考に実装しました。
例えば、ReliabilityとDurabilityは以下のパラメータで設定可能です。

Reliability Durability
RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT
RMW_QOS_POLICY_RELIABILITY_RELIABLE RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL
RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT RMW_QOS_POLICY_DURABILITY_VOLATILE

ROS2で用意されているQoSプロファイル一覧

以下はROS2で用意されているQoSプロファイル達になります。
これらは、/opt/ros/$ROS_DISTRO/include/rmw/qos_profiles.hを見ながら並べました。

  • rmw_qos_profile_sensor_data
  • rmw_qos_profile_parameters
  • rmw_qos_profile_default
  • rmw_qos_profile_services_default
  • rmw_qos_profile_parameter_events
  • rmw_qos_profile_system_default
  • rmw_qos_profile_unknown

何か間違いやご意見等があればコメントください。

1
0
0

Register as a new user and use Qiita more conveniently

  1. You get articles that match your needs
  2. You can efficiently read back useful information
  3. You can use dark theme
What you can do with signing up
1
0

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?