Skip to content

Commit

Permalink
fix(hesai_ros_wrapper): remove changes wrongly merged during rebase
Browse files Browse the repository at this point in the history
  • Loading branch information
mojomex committed Apr 4, 2024
1 parent d839329 commit fdbeb45
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions nebula_ros/src/hesai/hesai_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<nebula_msgs::msg::NebulaPacket>(
"hesai_packets", rclcpp::SensorDataQoS());

Expand Down Expand Up @@ -137,8 +139,6 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector<uint8_t> & pa

void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr<nebula_msgs::msg::NebulaPacket> packet_msg)
{
std::lock_guard lock(mtx_decode_);

auto t_start = std::chrono::high_resolution_clock::now();
std::tuple<nebula::drivers::NebulaPointCloudPtr, double> pointcloud_ts =
driver_ptr_->ParseCloudPacket(packet_msg->data);
Expand Down Expand Up @@ -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_;
}
Expand Down

0 comments on commit fdbeb45

Please sign in to comment.