Skip to content

File continental_ars548_hw_interface.hpp

File List > include > nebula_hw_interfaces > nebula_hw_interfaces_continental > continental_ars548_hw_interface.hpp

Go to the documentation of this file

// Copyright 2024 TIER IV, Inc.
//
// 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.

#ifndef NEBULA_CONTINENTAL_ARS548_HW_INTERFACE_H
#define NEBULA_CONTINENTAL_ARS548_HW_INTERFACE_H

#include "nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp"

#include <boost_udp_driver/udp_driver.hpp>
#include <nebula_common/continental/continental_ars548.hpp>
#include <rclcpp/rclcpp.hpp>

#include <nebula_msgs/msg/nebula_packet.hpp>

#include <memory>
#include <string>
#include <vector>

namespace nebula
{
namespace drivers
{
namespace continental_ars548
{
class ContinentalARS548HwInterface
{
public:
  ContinentalARS548HwInterface();

  Status SensorInterfaceStart();

  Status SensorInterfaceStop();

  Status SetSensorConfiguration(
    std::shared_ptr<const ContinentalARS548SensorConfiguration> sensor_configuration);

  Status RegisterPacketCallback(
    std::function<void(std::unique_ptr<nebula_msgs::msg::NebulaPacket>)> packet_callback);

  Status SetSensorMounting(
    float longitudinal_autosar, float lateral_autosar, float vertical_autosar, float yaw_autosar,
    float pitch_autosar, uint8_t plug_orientation);

  Status SetVehicleParameters(
    float length_autosar, float width_autosar, float height_autosar, float wheel_base_autosar);

  Status SetRadarParameters(
    uint16_t maximum_distance, uint8_t frequency_slot, uint8_t cycle_time, uint8_t time_slot,
    uint8_t hcc, uint8_t power_save_standstill);

  Status SetSensorIPAddress(const std::string & sensor_ip_address);

  Status SetAccelerationLateralCog(float lateral_acceleration);

  Status SetAccelerationLongitudinalCog(float longitudinal_acceleration);

  Status SetCharacteristicSpeed(float characteristic_speed);

  Status SetDrivingDirection(int direction);

  Status SetSteeringAngleFrontAxle(float angle_rad);

  Status SetVelocityVehicle(float velocity);

  Status SetYawRate(float yaw_rate);

  void SetLogger(std::shared_ptr<rclcpp::Logger> node);

private:
  void PrintInfo(std::string info);

  void PrintError(std::string error);

  void PrintDebug(std::string debug);

  void ReceiveSensorPacketCallbackWithSender(
    std::vector<uint8_t> & buffer, const std::string & sender_ip);

  void ReceiveSensorPacketCallback(std::vector<uint8_t> & buffer);

  std::unique_ptr<::drivers::common::IoContext> sensor_io_context_ptr_;
  std::unique_ptr<::drivers::udp_driver::UdpDriver> sensor_udp_driver_ptr_;
  std::shared_ptr<const ContinentalARS548SensorConfiguration> config_ptr_;
  std::function<void(std::unique_ptr<nebula_msgs::msg::NebulaPacket>)> packet_callback_;

  std::shared_ptr<rclcpp::Logger> parent_node_logger_ptr_;
};
}  // namespace continental_ars548
}  // namespace drivers
}  // namespace nebula

#endif  // NEBULA_CONTINENTAL_ARS548_HW_INTERFACE_H