Skip to content

Commit

Permalink
feat(velodyne_ros_wrapper): add profiling log to velodyne (#51)
Browse files Browse the repository at this point in the history
Signed-off-by: Mehmet Emin BAŞOĞLU <[email protected]>
Co-authored-by: David Wong <[email protected]>
Co-authored-by: Abraham Monrroy Cano <[email protected]>
  • Loading branch information
3 people authored Aug 21, 2023
1 parent 8f33f79 commit 5d4b39a
Showing 1 changed file with 5 additions and 0 deletions.
5 changes: 5 additions & 0 deletions nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@ VelodyneDriverRosWrapper::VelodyneDriverRosWrapper(const rclcpp::NodeOptions & o
void VelodyneDriverRosWrapper::ReceiveScanMsgCallback(
const velodyne_msgs::msg::VelodyneScan::SharedPtr scan_msg)
{
auto t_start = std::chrono::high_resolution_clock::now();

// take packets out of scan msg
std::vector<velodyne_msgs::msg::VelodynePacket> pkt_msgs = scan_msg->packets;

Expand Down Expand Up @@ -85,6 +87,9 @@ void VelodyneDriverRosWrapper::ReceiveScanMsgCallback(
rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count());
PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_);
}

auto runtime = std::chrono::high_resolution_clock::now() - t_start;
RCLCPP_DEBUG(get_logger(), "PROFILING {'d_total': %lu, 'n_out': %lu}", runtime.count(), pointcloud->size());
}

void VelodyneDriverRosWrapper::PublishCloud(
Expand Down

0 comments on commit 5d4b39a

Please sign in to comment.