File continental_ars548_ros_wrapper.hpp
File List > continental > continental_ars548_ros_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/mt_queue.hpp"
#include "nebula_ros/common/parameter_descriptors.hpp"
#include "nebula_ros/continental/continental_ars548_decoder_wrapper.hpp"
#include "nebula_ros/continental/continental_ars548_hw_interface_wrapper.hpp"
#include <nebula_common/continental/continental_ars548.hpp>
#include <nebula_common/nebula_common.hpp>
#include <nebula_common/nebula_status.hpp>
#include <nebula_hw_interfaces/nebula_hw_interfaces_continental/continental_ars548_hw_interface.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_components/register_node_macro.hpp>
#include <continental_msgs/msg/continental_ars548_detection_list.hpp>
#include <continental_msgs/msg/continental_ars548_object_list.hpp>
#include <nebula_msgs/msg/nebula_packet.hpp>
#include <memory>
#include <mutex>
#include <optional>
#include <thread>
#include <vector>
namespace nebula::ros
{
class ContinentalARS548RosWrapper final : public rclcpp::Node
{
public:
explicit ContinentalARS548RosWrapper(const rclcpp::NodeOptions & options);
~ContinentalARS548RosWrapper() noexcept override = default;
Status get_status();
Status stream_start();
private:
void receive_packet_callback(std::unique_ptr<nebula_msgs::msg::NebulaPacket> packet_msg_ptr);
void receive_packets_callback(std::unique_ptr<nebula_msgs::msg::NebulaPackets> packets_msg_ptr);
Status declare_and_get_sensor_config_params();
rcl_interfaces::msg::SetParametersResult on_parameter_change(
const std::vector<rclcpp::Parameter> & p);
Status validate_and_set_config(
std::shared_ptr<const drivers::continental_ars548::ContinentalARS548SensorConfiguration> &
new_config);
Status wrapper_status_;
std::shared_ptr<const drivers::continental_ars548::ContinentalARS548SensorConfiguration>
config_ptr_{};
MtQueue<std::unique_ptr<nebula_msgs::msg::NebulaPacket>> packet_queue_;
std::thread decoder_thread_;
rclcpp::Subscription<nebula_msgs::msg::NebulaPackets>::SharedPtr packets_sub_{};
bool launch_hw_{};
std::optional<ContinentalARS548HwInterfaceWrapper> hw_interface_wrapper_{};
std::optional<ContinentalARS548DecoderWrapper> decoder_wrapper_{};
std::mutex mtx_config_;
OnSetParametersCallbackHandle::SharedPtr parameter_event_cb_{};
};
} // namespace nebula::ros