Program Listing for File node.hpp
↰ Return to documentation for file (/tmp/ws/src/off_highway_sensor_drivers/off_highway_premium_radar/include/off_highway_premium_radar/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 <vector>
#include "rclcpp/rclcpp.hpp"
#include "io_context/io_context.hpp"
#include "off_highway_premium_radar/driver.hpp"
#include "off_highway_premium_radar/interface/converter.hpp"
namespace off_highway_premium_radar
{
class Node : public rclcpp::Node
{
public:
using Converters = std::vector<Converter::SharedPtr>;
explicit Node(
const std::string & node_name,
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
void configure(Converters converters);
private:
void declare_and_get_parameters();
std::shared_ptr<Driver> driver_;
// 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