Program Listing for File driver.hpp

Return to documentation for file (/tmp/ws/src/off_highway_sensor_drivers/off_highway_premium_radar/include/off_highway_premium_radar/driver.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 <string>
#include <vector>

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

#include "off_highway_premium_radar/location_data_handler.hpp"
#include "off_highway_premium_radar/pdu_definitions.hpp"
#include "off_highway_premium_radar/udp_socket.hpp"
#include "off_highway_premium_radar/interface/receiver.hpp"
#include "off_highway_premium_radar/interface/sender.hpp"

namespace off_highway_premium_radar
{

class Driver : public Sender
{
public:
  using Receivers = std::vector<Receiver::SharedPtr>;

  explicit Driver(
    const std::string & host_ip, const int host_port, const std::string & sensor_ip,
    const int sensor_port, bool connect);

  virtual ~Driver() = default;

  void start_receiving();

  void register_receiver(Receiver::SharedPtr receiver) {receivers_.emplace_back(receiver);}

  bool send_ego_vehicle_data(EgoVehicleInput & data) override {return send(data);}

  bool send_measurement_cycle_sync(MeasurementCycleSynchronisation & data) override
  {
    return send(data);
  }
  bool send_sensor_mode_request(SensorModeRequest & data) override {return send(data);}

  bool send_measurement_program(MeasurementProgram & data) override {return send(data);}

private:
  void callback_udp(
    const std::vector<uint8_t> & buffer, const std::string & source_ip,
    const uint32_t source_port);

  template<class Input>
  bool send(Input data)
  {
    auto buffer = data.serialize();
    // TODO(rcp1-beg) Really check if complete buffer was sent?
    return udp_socket_.send(buffer) == buffer.size();
  }

  enum class PduType
  {
    kLocationData,
    kSensorFeedback,
    kStateInformation,
    kSensorBroadcast,
    kLocationAttributes,
    kSensorDtcInformation,
    kUnknown
  };

  PduType get_pdu_type(std::vector<uint8_t> buffer);

  // Socket handling
  IoContext ctx_;
  UdpSocket udp_socket_;

  LocationDataHandler location_data_handler_;

  Receivers receivers_;
};

}  // namespace off_highway_premium_radar