Skip to content

File continental_ars548_hw_interface_wrapper.hpp

File List > continental > continental_ars548_hw_interface_wrapper.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.

#pragma once

#include "nebula_ros/common/parameter_descriptors.hpp"

#include <nebula_common/continental/continental_ars548.hpp>
#include <nebula_hw_interfaces/nebula_hw_interfaces_continental/continental_ars548_hw_interface.hpp>
#include <rclcpp/rclcpp.hpp>

#include <continental_srvs/srv/continental_ars548_set_network_configuration.hpp>
#include <continental_srvs/srv/continental_ars548_set_radar_parameters.hpp>
#include <continental_srvs/srv/continental_ars548_set_sensor_mounting.hpp>
#include <continental_srvs/srv/continental_ars548_set_vehicle_parameters.hpp>
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
#include <geometry_msgs/msg/twist_with_covariance_stamped.hpp>
#include <std_msgs/msg/float32.hpp>

#include <memory>

namespace nebula
{
namespace ros
{
class ContinentalARS548HwInterfaceWrapper
{
public:
  ContinentalARS548HwInterfaceWrapper(
    rclcpp::Node * const parent_node,
    std::shared_ptr<const drivers::continental_ars548::ContinentalARS548SensorConfiguration> &
      config);

  void SensorInterfaceStart();

  void OnConfigChange(
    const std::shared_ptr<const drivers::continental_ars548::ContinentalARS548SensorConfiguration> &
      new_config_ptr);

  nebula::Status Status();

  std::shared_ptr<drivers::continental_ars548::ContinentalARS548HwInterface> HwInterface() const;

private:
  void OdometryCallback(const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg);

  void AccelerationCallback(const geometry_msgs::msg::AccelWithCovarianceStamped::SharedPtr msg);

  void SteeringAngleCallback(const std_msgs::msg::Float32::SharedPtr msg);

  void SetNetworkConfigurationRequestCallback(
    const std::shared_ptr<continental_srvs::srv::ContinentalArs548SetNetworkConfiguration::Request>
      request,
    const std::shared_ptr<continental_srvs::srv::ContinentalArs548SetNetworkConfiguration::Response>
      response);

  void SetSensorMountingRequestCallback(
    const std::shared_ptr<continental_srvs::srv::ContinentalArs548SetSensorMounting::Request>
      request,
    const std::shared_ptr<continental_srvs::srv::ContinentalArs548SetSensorMounting::Response>
      response);

  void SetVehicleParametersRequestCallback(
    const std::shared_ptr<continental_srvs::srv::ContinentalArs548SetVehicleParameters::Request>
      request,
    const std::shared_ptr<continental_srvs::srv::ContinentalArs548SetVehicleParameters::Response>
      response);

  void SetRadarParametersRequestCallback(
    const std::shared_ptr<continental_srvs::srv::ContinentalArs548SetRadarParameters::Request>
      request,
    const std::shared_ptr<continental_srvs::srv::ContinentalArs548SetRadarParameters::Response>
      response);

  rclcpp::Node * const parent_node_;
  std::shared_ptr<drivers::continental_ars548::ContinentalARS548HwInterface> hw_interface_{};
  rclcpp::Logger logger_;
  nebula::Status status_{};
  std::shared_ptr<const nebula::drivers::continental_ars548::ContinentalARS548SensorConfiguration>
    config_ptr_{};

  rclcpp::Subscription<geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr odometry_sub_{};
  rclcpp::Subscription<geometry_msgs::msg::AccelWithCovarianceStamped>::SharedPtr
    acceleration_sub_{};
  rclcpp::Subscription<std_msgs::msg::Float32>::SharedPtr steering_angle_sub_{};

  bool standstill_{true};

  rclcpp::Service<continental_srvs::srv::ContinentalArs548SetNetworkConfiguration>::SharedPtr
    set_network_configuration_service_server_{};
  rclcpp::Service<continental_srvs::srv::ContinentalArs548SetSensorMounting>::SharedPtr
    set_sensor_mounting_service_server_{};
  rclcpp::Service<continental_srvs::srv::ContinentalArs548SetVehicleParameters>::SharedPtr
    set_vehicle_parameters_service_server_{};
  rclcpp::Service<continental_srvs::srv::ContinentalArs548SetRadarParameters>::SharedPtr
    set_radar_parameters_service_server_{};
};
}  // namespace ros
}  // namespace nebula