Skip to content

Commit

Permalink
feat: update pcd package
Browse files Browse the repository at this point in the history
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
  • Loading branch information
taikitanaka3 committed May 24, 2022
1 parent b57348c commit 705df15
Show file tree
Hide file tree
Showing 9 changed files with 30 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ void VoxelBasedApproximateCompareMapFilterComponent::filter(
return;
}
// add processing time for debug
if (stop_watch_ptr_) {
if (debug_publisher_) {
const double processing_time_ms = stop_watch_ptr_->toc(true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ void VoxelBasedCompareMapFilterComponent::filter(
return;
}
// add processing time for debug
if (stop_watch_ptr_) {
if (debug_publisher_) {
const double processing_time_ms = stop_watch_ptr_->toc(true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
Expand Down
2 changes: 1 addition & 1 deletion perception/lidar_apollo_instance_segmentation/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ void LidarInstanceSegmentationNode::pointCloudCallback(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
{
// add processing time for debug
if (stop_watch_ptr_) {
if (debug_publisher_) {
const double processing_time_ms = stop_watch_ptr_->toc(true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -230,7 +230,7 @@ void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2(
return;
}
// add processing time for debug
if (stop_watch_ptr_) {
if (debug_publisher_) {
const double processing_time_ms = stop_watch_ptr_->toc(true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,9 @@
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <tier4_debug_msgs/msg/int32_stamped.hpp>
#include <tier4_debug_msgs/msg/string_stamped.hpp>
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
#include <tier4_autoware_utils/system/stop_watch.hpp>


#include <message_filters/pass_through.h>
#include <message_filters/subscriber.h>
Expand Down Expand Up @@ -165,6 +168,11 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
void timer_callback();

void checkConcatStatus(diagnostic_updater::DiagnosticStatusWrapper & stat);

/** \brief processing time publisher. **/
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
std::unique_ptr<tier4_autoware_utils::DebugPublisher> debug_publisher_;

};

} // namespace pointcloud_preprocessor
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,15 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro
const rclcpp::NodeOptions & node_options)
: Node("point_cloud_concatenator_component", node_options)
{
// initialize debug tool
{
using tier4_autoware_utils::DebugPublisher;
using tier4_autoware_utils::StopWatch;
stop_watch_ptr_ = std::make_unique<StopWatch<std::chrono::milliseconds>>();
debug_publisher_ = std::make_unique<DebugPublisher>(this, "concatenate_data_synchronizer");
stop_watch_ptr_->tic();
}

// Set parameters
{
output_frame_ = static_cast<std::string>(declare_parameter("output_frame", ""));
Expand Down Expand Up @@ -260,6 +269,12 @@ void PointCloudConcatenateDataSynchronizerComponent::combineClouds(

void PointCloudConcatenateDataSynchronizerComponent::publish()
{
// add processing time for debug
if (debug_publisher_) {
const double processing_time_ms = stop_watch_ptr_->toc(true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
}
sensor_msgs::msg::PointCloud2::SharedPtr concat_cloud_ptr_ = nullptr;
not_subscribed_topic_names_.clear();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ void CropBoxFilterComponent::filter(
{
std::scoped_lock lock(mutex_);
// add processing time for debug
if (stop_watch_ptr_) {
if (debug_publisher_) {
const double processing_time_ms = stop_watch_ptr_->toc(true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ void DistortionCorrectorComponent::onPointCloud(PointCloud2::UniquePtr points_ms
}

// add processing time for debug
if (stop_watch_ptr_) {
if (debug_publisher_) {
const double processing_time_ms = stop_watch_ptr_->toc(true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ void RingOutlierFilterComponent::filter(
{
std::scoped_lock lock(mutex_);
// add processing time for debug
if (stop_watch_ptr_) {
if (debug_publisher_) {
const double processing_time_ms = stop_watch_ptr_->toc(true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
Expand Down

0 comments on commit 705df15

Please sign in to comment.