Skip to content
Open
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 @@ -418,6 +418,12 @@ radar_msgs::msg::RadarTracks ContinentalSRR520DecoderWrapper::convert_to_radar_t
visualization_msgs::msg::MarkerArray ContinentalSRR520DecoderWrapper::convert_to_markers(
const continental_msgs::msg::ContinentalSrr520ObjectList & msg)
{
std::string base_frame;
{
std::lock_guard lock(mtx_driver_ptr_);
base_frame = sensor_cfg_->base_frame;
}

visualization_msgs::msg::MarkerArray marker_array;
marker_array.markers.reserve(4 * msg.objects.size());

Expand Down Expand Up @@ -481,7 +487,7 @@ visualization_msgs::msg::MarkerArray ContinentalSRR520DecoderWrapper::convert_to
current_ids.emplace(object.object_id);

visualization_msgs::msg::Marker box_marker;
box_marker.header.frame_id = sensor_cfg_->base_frame;
box_marker.header.frame_id = base_frame;
box_marker.header.stamp = msg.header.stamp;
box_marker.ns = "boxes";
box_marker.id = object.object_id;
Expand Down Expand Up @@ -556,7 +562,7 @@ visualization_msgs::msg::MarkerArray ContinentalSRR520DecoderWrapper::convert_to
}

visualization_msgs::msg::Marker delete_marker;
delete_marker.header.frame_id = sensor_cfg_->base_frame;
delete_marker.header.frame_id = base_frame;
delete_marker.header.stamp = msg.header.stamp;
delete_marker.ns = "boxes";
delete_marker.id = previous_id;
Expand Down
8 changes: 6 additions & 2 deletions nebula_ros/src/hesai/decoder_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,7 @@ void HesaiDecoderWrapper::on_calibration_change(
drivers::PacketDecodeResult HesaiDecoderWrapper::process_cloud_packet(
std::unique_ptr<nebula_msgs::msg::NebulaPacket> packet_msg, uint64_t receive_time_ns)
{
std::lock_guard lock(mtx_driver_ptr_);
current_scan_perf_counters_.receive_time_current_scan_ns += receive_time_ns;

// Ideally, we would only accumulate packets if someone is subscribed to the packets topic.
Expand All @@ -131,7 +132,6 @@ drivers::PacketDecodeResult HesaiDecoderWrapper::process_cloud_packet(
current_scan_msg_->packets.emplace_back(pandar_packet_msg);
}

std::lock_guard lock(mtx_driver_ptr_);
auto decode_result = driver_ptr_->parse_cloud_packet(packet_msg->data);

current_scan_perf_counters_.decode_time_current_scan_ns +=
Expand Down Expand Up @@ -216,7 +216,11 @@ void HesaiDecoderWrapper::publish_cloud(
if (pointcloud->header.stamp.sec < 0) {
RCLCPP_WARN_STREAM(logger_, "Timestamp error, verify clock source.");
}
pointcloud->header.frame_id = sensor_cfg_->frame_id;

{
std::lock_guard lock(mtx_driver_ptr_);
pointcloud->header.frame_id = sensor_cfg_->frame_id;
}
publisher->publish(std::move(pointcloud));
}

Expand Down
6 changes: 5 additions & 1 deletion nebula_ros/src/robosense/decoder_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,11 @@ void RobosenseDecoderWrapper::publish_cloud(
RCLCPP_WARN_STREAM(logger_, "Timestamp error, verify clock source.");
return;
}
pointcloud->header.frame_id = sensor_cfg_->frame_id;

{
std::lock_guard lock(mtx_driver_ptr_);
pointcloud->header.frame_id = sensor_cfg_->frame_id;
}
publisher->publish(std::move(pointcloud));
}

Expand Down
13 changes: 10 additions & 3 deletions nebula_ros/src/velodyne/decoder_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,8 +130,11 @@ rcl_interfaces::msg::SetParametersResult VelodyneDecoderWrapper::on_parameter_ch
}

on_calibration_change(get_calibration_result.value());
RCLCPP_INFO_STREAM(
logger_, "Changed calibration to '" << calibration_cfg_ptr_->calibration_file << "'");
{
std::lock_guard lock(mtx_driver_ptr_);
RCLCPP_INFO_STREAM(
logger_, "Changed calibration to '" << calibration_cfg_ptr_->calibration_file << "'");
}
return rcl_interfaces::build<SetParametersResult>().successful(true).reason("");
}

Expand Down Expand Up @@ -238,7 +241,11 @@ void VelodyneDecoderWrapper::publish_cloud(
if (pointcloud->header.stamp.sec < 0) {
RCLCPP_WARN_STREAM(logger_, "Timestamp error, verify clock source.");
}
pointcloud->header.frame_id = sensor_cfg_->frame_id;

{
std::lock_guard lock(mtx_driver_ptr_);
pointcloud->header.frame_id = sensor_cfg_->frame_id;
}
publisher->publish(std::move(pointcloud));
}

Expand Down
Loading