From fdbeb45e2cb04ddb3a032c9c9d39c34143a3fb14 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 4 Apr 2024 19:35:25 +0900 Subject: [PATCH] fix(hesai_ros_wrapper): remove changes wrongly merged during rebase --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 8957a30d2..9aef30110 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -91,6 +91,8 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); + //TODO(mojomex): create high-frequency QoS with large buffer to prevent packet loss + packet_pub_ = create_publisher( "hesai_packets", rclcpp::SensorDataQoS()); @@ -137,8 +139,6 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & pa void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) { - std::lock_guard lock(mtx_decode_); - auto t_start = std::chrono::high_resolution_clock::now(); std::tuple pointcloud_ts = driver_ptr_->ParseCloudPacket(packet_msg->data); @@ -742,7 +742,7 @@ HesaiRosWrapper::~HesaiRosWrapper() Status HesaiRosWrapper::StreamStart() { if (Status::OK == interface_status_) { - interface_status_ = hw_interface_.CloudInterfaceStart(); + interface_status_ = hw_interface_.SensorInterfaceStart(); } return interface_status_; }