Skip to content

Commit

Permalink
feat(hesai_ros_wrapper): print warning when connected to HW and recei…
Browse files Browse the repository at this point in the history
…ving /pandar_packets
  • Loading branch information
mojomex committed Apr 11, 2024
1 parent 0215d7c commit d0f10cb
Showing 1 changed file with 5 additions and 11 deletions.
16 changes: 5 additions & 11 deletions nebula_ros/src/hesai/hesai_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,11 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options)
StreamStart();
hw_interface_.RegisterScanCallback(
std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1));
} else {
packets_sub_ = create_subscription<pandar_msgs::msg::PandarScan>("pandar_packets", rclcpp::SensorDataQoS(), std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1));
}

packets_sub_ = create_subscription<pandar_msgs::msg::PandarScan>("pandar_packets", rclcpp::SensorDataQoS(),
std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1));

set_param_res_ = this->add_on_set_parameters_callback(
std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1));
}
Expand Down Expand Up @@ -104,15 +105,8 @@ Status HesaiRosWrapper::InitializeDecoder()
rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile);

decoder_thread_ = std::thread([this]() {
std::deque<std::unique_ptr<nebula_msgs::msg::NebulaPacket>> received{};
while (true) {
packet_queue_.pop_all(received);

while (!received.empty()) {
auto pkt = std::move(received.back());
received.pop_back();
this->ProcessCloudPacket(std::move(pkt));
}
this->ProcessCloudPacket(std::move(packet_queue_.pop()));
}
});

Expand Down Expand Up @@ -242,7 +236,7 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr<nebula_msgs::msg::Nebul

// Accumulate packets for recording only if someone is subscribed to the topic (for performance)
if (
pandar_scan_pub_ &&
launch_hw_ &&
(pandar_scan_pub_->get_subscription_count() > 0 ||
pandar_scan_pub_->get_intra_process_subscription_count() > 0)) {
if (current_scan_msg_->packets.size() == 0) {
Expand Down

0 comments on commit d0f10cb

Please sign in to comment.