Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

perf(ars548): remove mtqueue #275

Merged
merged 4 commits into from
Mar 5, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion nebula_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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 ARS548)
string(TOLOWER ${MODEL}_smoke_test test_name)
add_ros_test(
test/smoke_test.py
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@

#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"
Expand Down Expand Up @@ -80,11 +79,6 @@ class ContinentalARS548RosWrapper final : public rclcpp::Node
std::shared_ptr<const drivers::continental_ars548::ContinentalARS548SensorConfiguration>
config_ptr_{};

/// @brief Stores received packets that have not been processed yet by the decoder thread
MtQueue<std::unique_ptr<nebula_msgs::msg::NebulaPacket>> packet_queue_;
/// @brief Thread to isolate decoding from receiving
std::thread decoder_thread_;

rclcpp::Subscription<nebula_msgs::msg::NebulaPackets>::SharedPtr packets_sub_{};

bool launch_hw_{};
Expand Down
17 changes: 3 additions & 14 deletions nebula_ros/src/continental/continental_ars548_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,7 @@ namespace nebula::ros
ContinentalARS548RosWrapper::ContinentalARS548RosWrapper(const rclcpp::NodeOptions & options)
: rclcpp::Node(
"continental_ars548_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)),
wrapper_status_(Status::NOT_INITIALIZED),
packet_queue_(3000),
hw_interface_wrapper_(),
decoder_wrapper_()
wrapper_status_(Status::NOT_INITIALIZED)
{
setvbuf(stdout, NULL, _IONBF, BUFSIZ);

Expand All @@ -54,12 +51,6 @@ ContinentalARS548RosWrapper::ContinentalARS548RosWrapper(const rclcpp::NodeOptio

RCLCPP_DEBUG(get_logger(), "Starting stream");

decoder_thread_ = std::thread([this]() {
while (true) {
decoder_wrapper_->process_packet(packet_queue_.pop());
}
});

if (launch_hw_) {
hw_interface_wrapper_->hw_interface()->register_packet_callback(std::bind(
&ContinentalARS548RosWrapper::receive_packet_callback, this, std::placeholders::_1));
Expand Down Expand Up @@ -155,7 +146,7 @@ void ContinentalARS548RosWrapper::receive_packets_callback(
nebula_packet_ptr->stamp = packet.stamp;
nebula_packet_ptr->data = std::move(packet.data);

packet_queue_.push(std::move(nebula_packet_ptr));
decoder_wrapper_->process_packet(std::move(nebula_packet_ptr));
}
}

Expand All @@ -166,9 +157,7 @@ void ContinentalARS548RosWrapper::receive_packet_callback(
return;
}

if (!packet_queue_.try_push(std::move(msg_ptr))) {
RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packet(s) dropped");
}
decoder_wrapper_->process_packet(std::move(msg_ptr));
}

Status ContinentalARS548RosWrapper::get_status()
Expand Down
Loading