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

fix(robosense): include DIFOP packets in record/replay functionality #213

Merged
merged 1 commit into from
Nov 1, 2024
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
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ class RobosenseDriver : NebulaDriverBase
{
private:
/// @brief Current driver status
Status driver_status_;
Status driver_status_{Status::NOT_INITIALIZED};

/// @brief Decoder according to the model
std::shared_ptr<RobosenseScanDecoder> scan_decoder_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include <rclcpp_components/register_node_macro.hpp>

#include <nebula_msgs/msg/nebula_packet.hpp>
#include <robosense_msgs/msg/detail/robosense_info_packet__struct.hpp>
#include <robosense_msgs/msg/robosense_info_packet.hpp>
#include <robosense_msgs/msg/robosense_scan.hpp>

Expand Down Expand Up @@ -81,14 +82,17 @@ class RobosenseRosWrapper final : public rclcpp::Node

nebula::Status wrapper_status_;

std::shared_ptr<const nebula::drivers::RobosenseSensorConfiguration> sensor_cfg_ptr_{};
std::shared_ptr<const nebula::drivers::RobosenseSensorConfiguration> sensor_cfg_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<robosense_msgs::msg::RobosenseScan>::SharedPtr packets_sub_{};
rclcpp::Publisher<robosense_msgs::msg::RobosenseInfoPacket>::SharedPtr info_packets_pub_;

rclcpp::Subscription<robosense_msgs::msg::RobosenseScan>::SharedPtr packets_sub_;
rclcpp::Subscription<robosense_msgs::msg::RobosenseInfoPacket>::SharedPtr info_packets_sub_;

bool launch_hw_;

Expand Down
42 changes: 35 additions & 7 deletions nebula_ros/src/robosense/robosense_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,13 @@

#include "nebula_ros/common/parameter_descriptors.hpp"

#include <rclcpp/qos.hpp>

#include <robosense_msgs/msg/detail/robosense_info_packet__struct.hpp>

#include <algorithm>
#include <iterator>

#pragma clang diagnostic ignored "-Wbitwise-instead-of-logical"

namespace nebula::ros
Expand All @@ -12,10 +19,7 @@
: 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),
hw_interface_wrapper_(),
hw_monitor_wrapper_(),
decoder_wrapper_()
packet_queue_(3000)

Check warning on line 22 in nebula_ros/src/robosense/robosense_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/robosense/robosense_ros_wrapper.cpp#L22

Added line #L22 was not covered by tests
{
setvbuf(stdout, NULL, _IONBF, BUFSIZ);

Expand All @@ -28,23 +32,28 @@

RCLCPP_INFO_STREAM(get_logger(), "Sensor Configuration: " << *sensor_cfg_ptr_);

info_driver_.emplace(sensor_cfg_ptr_);

Check warning on line 35 in nebula_ros/src/robosense/robosense_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/robosense/robosense_ros_wrapper.cpp#L35

Added line #L35 was not covered by tests

launch_hw_ = declare_parameter<bool>("launch_hw", param_read_only());

if (launch_hw_) {
hw_interface_wrapper_.emplace(this, sensor_cfg_ptr_);
hw_monitor_wrapper_.emplace(this, sensor_cfg_ptr_);
info_driver_.emplace(sensor_cfg_ptr_);
}

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_msgs::msg::RobosenseInfoPacket>("robosense_info_packets", 10);

Check warning on line 55 in nebula_ros/src/robosense/robosense_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/robosense/robosense_ros_wrapper.cpp#L55

Added line #L55 was not covered by tests

hw_interface_wrapper_->hw_interface()->register_scan_callback(
std::bind(&RobosenseRosWrapper::receive_cloud_packet_callback, this, std::placeholders::_1));
hw_interface_wrapper_->hw_interface()->register_info_callback(
Expand All @@ -54,9 +63,16 @@
packets_sub_ = create_subscription<robosense_msgs::msg::RobosenseScan>(
"robosense_packets", rclcpp::SensorDataQoS(),
std::bind(&RobosenseRosWrapper::receive_scan_message_callback, this, std::placeholders::_1));
info_packets_sub_ = create_subscription<robosense_msgs::msg::RobosenseInfoPacket>(
"robosense_info_packets", 10, [this](const robosense_msgs::msg::RobosenseInfoPacket & msg) {

Check warning on line 67 in nebula_ros/src/robosense/robosense_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/robosense/robosense_ros_wrapper.cpp#L66-L67

Added lines #L66 - L67 were not covered by tests
std::vector<uint8_t> raw_packet;
std::copy(msg.packet.data.cbegin(), msg.packet.data.cend(), std::back_inserter(raw_packet));
receive_info_packet_callback(raw_packet);
});

Check warning on line 71 in nebula_ros/src/robosense/robosense_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/robosense/robosense_ros_wrapper.cpp#L70-L71

Added lines #L70 - L71 were not covered by tests
RCLCPP_INFO_STREAM(
get_logger(),
"Hardware connection disabled, listening for packets on " << packets_sub_->get_topic_name());
get_logger(), "Hardware connection disabled, listening for packets on "
<< packets_sub_->get_topic_name() << " and "
<< info_packets_sub_->get_topic_name());
}

// Register parameter callback after all params have been declared. Otherwise it would be called
Expand Down Expand Up @@ -153,6 +169,18 @@
"Wrapper already receiving packets despite not being fully initialized yet.");
}

if (info_packets_pub_) {
robosense_msgs::msg::RobosenseInfoPacket info_packet{};

Check warning on line 173 in nebula_ros/src/robosense/robosense_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/robosense/robosense_ros_wrapper.cpp#L173

Added line #L173 was not covered by tests
if (packet.size() != info_packet.packet.data.size()) {
RCLCPP_ERROR_THROTTLE(

Check warning on line 175 in nebula_ros/src/robosense/robosense_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/robosense/robosense_ros_wrapper.cpp#L175

Added line #L175 was not covered by tests
get_logger(), *get_clock(), 1000, "Could not publish info packet: size unsupported");
} else {
std::copy(packet.cbegin(), packet.cend(), info_packet.packet.data.begin());
info_packet.packet.stamp = now();
info_packets_pub_->publish(info_packet);

Check warning on line 180 in nebula_ros/src/robosense/robosense_ros_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

nebula_ros/src/robosense/robosense_ros_wrapper.cpp#L179-L180

Added lines #L179 - L180 were not covered by tests
}
}

auto status = info_driver_->decode_info_packet(packet);

if (status != nebula::Status::OK) {
Expand Down
Loading