Program Listing for File node.hpp

Return to documentation for file (include/off_highway_premium_radar_sample/node.hpp)

// Copyright 2023 Robert Bosch GmbH and its subsidiaries
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#pragma once

#include <cstdint>
#include <memory>
#include <string>
#include <tuple>
#include <variant>

#include "rclcpp/rclcpp.hpp"
#include "io_context/io_context.hpp"

#include "off_highway_premium_radar_sample/driver.hpp"
#include "off_highway_premium_radar_sample/interface/converter.hpp"

namespace off_highway_premium_radar_sample
{

template<typename ... Converters>
class Node : public rclcpp::Node
{
public:
  explicit Node(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());

  void configure();

private:
  void declare_and_get_parameters();

  std::shared_ptr<Driver> driver_;
  std::tuple<std::variant<std::shared_ptr<Converters>>...> converters_;
  rclcpp::TimerBase::SharedPtr configure_timer_;

  // Parameters
  std::string host_ip_;
  uint16_t host_port_{0x76C0};
  std::string sensor_ip_{"192.168.40.50"};
  uint16_t sensor_port_{0x76C6};
  bool connect_socket_{false};
};

}  // namespace off_highway_premium_radar_sample

#include "off_highway_premium_radar_sample/impl/node_impl.hpp"