diff --git a/nebula_ros/CMakeLists.txt b/nebula_ros/CMakeLists.txt index e4399af41..17b49db16 100644 --- a/nebula_ros/CMakeLists.txt +++ b/nebula_ros/CMakeLists.txt @@ -228,7 +228,7 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() - foreach(MODEL Pandar40P Pandar64 PandarQT64 PandarQT128 Pandar128E4X PandarAT128 PandarXT16 PandarXT32 PandarXT32M) + foreach(MODEL Pandar40P Pandar64 PandarQT64 PandarQT128 Pandar128E4X PandarAT128 PandarXT16 PandarXT32 PandarXT32M Helios Bpearl) string(TOLOWER ${MODEL}_smoke_test test_name) add_ros_test( test/smoke_test.py diff --git a/nebula_ros/include/nebula_ros/robosense/robosense_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/robosense/robosense_ros_wrapper.hpp index 2c7e08d00..018382589 100644 --- a/nebula_ros/include/nebula_ros/robosense/robosense_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/robosense/robosense_ros_wrapper.hpp @@ -14,7 +14,6 @@ #pragma once -#include "nebula_ros/common/mt_queue.hpp" #include "nebula_ros/robosense/decoder_wrapper.hpp" #include "nebula_ros/robosense/hw_interface_wrapper.hpp" #include "nebula_ros/robosense/hw_monitor_wrapper.hpp" @@ -84,11 +83,6 @@ class RobosenseRosWrapper final : public rclcpp::Node std::shared_ptr sensor_cfg_ptr_; - /// @brief Stores received packets that have not been processed yet by the decoder thread - MtQueue> packet_queue_; - /// @brief Thread to isolate decoding from receiving - std::thread decoder_thread_; - rclcpp::Publisher::SharedPtr info_packets_pub_; rclcpp::Subscription::SharedPtr packets_sub_; diff --git a/nebula_ros/src/robosense/robosense_ros_wrapper.cpp b/nebula_ros/src/robosense/robosense_ros_wrapper.cpp index 8759431d2..5b873db85 100644 --- a/nebula_ros/src/robosense/robosense_ros_wrapper.cpp +++ b/nebula_ros/src/robosense/robosense_ros_wrapper.cpp @@ -24,8 +24,7 @@ namespace nebula::ros RobosenseRosWrapper::RobosenseRosWrapper(const rclcpp::NodeOptions & options) : rclcpp::Node("robosense_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)), wrapper_status_(Status::NOT_INITIALIZED), - sensor_cfg_ptr_(nullptr), - packet_queue_(3000) + sensor_cfg_ptr_(nullptr) { setvbuf(stdout, NULL, _IONBF, BUFSIZ); @@ -48,13 +47,6 @@ RobosenseRosWrapper::RobosenseRosWrapper(const rclcpp::NodeOptions & options) RCLCPP_DEBUG(get_logger(), "Starting stream"); - decoder_thread_ = std::thread([this]() { - while (true) { - if (!decoder_wrapper_) continue; - decoder_wrapper_->process_cloud_packet(packet_queue_.pop()); - } - }); - if (launch_hw_) { info_packets_pub_ = create_publisher("robosense_info_packets", 10); @@ -158,12 +150,16 @@ void RobosenseRosWrapper::receive_scan_message_callback( return; } + if (!decoder_wrapper_ || decoder_wrapper_->status() != Status::OK) { + return; + } + for (auto & pkt : scan_msg->packets) { auto nebula_pkt_ptr = std::make_unique(); nebula_pkt_ptr->stamp = pkt.stamp; std::copy(pkt.data.begin(), pkt.data.end(), std::back_inserter(nebula_pkt_ptr->data)); - packet_queue_.push(std::move(nebula_pkt_ptr)); + decoder_wrapper_->process_cloud_packet(std::move(nebula_pkt_ptr)); } } @@ -312,9 +308,7 @@ void RobosenseRosWrapper::receive_cloud_packet_callback(std::vector & p msg_ptr->stamp.nanosec = static_cast(timestamp_ns % 1'000'000'000); msg_ptr->data.swap(packet); - if (!packet_queue_.try_push(std::move(msg_ptr))) { - RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packet(s) dropped"); - } + decoder_wrapper_->process_cloud_packet(std::move(msg_ptr)); } RCLCPP_COMPONENTS_REGISTER_NODE(RobosenseRosWrapper) diff --git a/nebula_ros/test/smoke_test.py b/nebula_ros/test/smoke_test.py index b509ffe59..9eedff48e 100644 --- a/nebula_ros/test/smoke_test.py +++ b/nebula_ros/test/smoke_test.py @@ -37,7 +37,7 @@ def generate_test_description(): class TestCorrectStartup(unittest.TestCase): def test_wait_for_startup_then_shutdown(self): self.proc_output: launch_testing.ActiveIoHandler - self.proc_output.assertWaitFor("Wrapper=OK", timeout=2) + self.proc_output.assertWaitFor("Hardware connection disabled", timeout=2) @launch_testing.post_shutdown_test()