Aws::AwsError ReadSubscriberList()

in cloudwatch_logger/src/log_node_param_helper.cpp [173:196]


Aws::AwsError ReadSubscriberList(
  const bool subscribe_to_rosout,
  const std::shared_ptr<Aws::Client::ParameterReaderInterface>& parameter_reader,
  std::function<void(const rcl_interfaces::msg::Log::SharedPtr)> callback,
  const rclcpp::Node::SharedPtr& nh,
  std::vector<rclcpp::Subscription<rcl_interfaces::msg::Log>::SharedPtr> & subscriptions)
{
  std::vector<std::string> topics;
  Aws::AwsError ret = parameter_reader->ReadParam(ParameterPath(kNodeParamLogTopicsListKey), topics);

  for (const std::string & topic : topics) {
    rclcpp::Subscription<rcl_interfaces::msg::Log>::SharedPtr sub
      = nh->create_subscription<rcl_interfaces::msg::Log>(topic, kNodeSubQueueSize, callback);
    AWS_LOGSTREAM_INFO(__func__, "Subscribing to topic: " << topic);
    subscriptions.push_back(sub);
  }
  if (subscribe_to_rosout) {
    rclcpp::Subscription<rcl_interfaces::msg::Log>::SharedPtr sub
      = nh->create_subscription<rcl_interfaces::msg::Log>(kNodeRosoutAggregatedTopicName, kNodeSubQueueSize, callback);
    AWS_LOG_INFO(__func__, "Subscribing to rosout_agg");
    subscriptions.push_back(sub);
  }
  return ret;
}