From a06f1cd0c037c17a84652fad2078b6283a101dfe Mon Sep 17 00:00:00 2001 From: Robot Date: Tue, 31 Oct 2023 10:23:49 +0800 Subject: [PATCH] update 10_pc_objects --- demo_cpp/10_pc_objects.cpp | 23 +++++++++++------------ demo_cpp/10_pc_objects_class.cpp | 19 ++++++++++--------- 2 files changed, 21 insertions(+), 21 deletions(-) diff --git a/demo_cpp/10_pc_objects.cpp b/demo_cpp/10_pc_objects.cpp index 5b6b9de..179b28e 100644 --- a/demo_cpp/10_pc_objects.cpp +++ b/demo_cpp/10_pc_objects.cpp @@ -1,14 +1,13 @@ #include #include -#include #include #include +#include #include #include -#include +#include #include #include -#include std::shared_ptr node; tf2_ros::Buffer::SharedPtr tf_buffer_; @@ -20,7 +19,7 @@ void PointcloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg) "base_footprint", msg->header.frame_id, msg->header.stamp - ); + ); if (!result) { return; @@ -31,7 +30,7 @@ void PointcloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg) *msg, pc_footprint, *tf_buffer_ - ); + ); pcl::PointCloud cloud_src; pcl::fromROSMsg(pc_footprint, cloud_src); @@ -106,13 +105,13 @@ void PointcloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg) float object_y = points_y_sum/point_num; float object_z = points_z_sum/point_num; RCLCPP_INFO( - node->get_logger(), - "object-%d pos=( %.2f , %.2f , %.2f)" , - i, - object_x, - object_y, - object_z - ); + node->get_logger(), + "object %d pos=(%.2f , %.2f , %.2f)", + i, + object_x, + object_y, + object_z + ); } RCLCPP_INFO(node->get_logger(), "---------------------" ); } diff --git a/demo_cpp/10_pc_objects_class.cpp b/demo_cpp/10_pc_objects_class.cpp index 8c49c18..78a0a4a 100644 --- a/demo_cpp/10_pc_objects_class.cpp +++ b/demo_cpp/10_pc_objects_class.cpp @@ -1,28 +1,28 @@ #include #include -#include #include #include +#include #include #include -#include +#include #include #include -#include class PointcloudObjects : public rclcpp::Node { public: PointcloudObjects() - : Node("pointcloud_cluster") + : Node("pointcloud_objects_node") { tf_buffer_ = std::make_shared(this->get_clock()); tf_listener_ = std::make_shared(*tf_buffer_); pc_sub_ = this->create_subscription( - "/kinect2/sd/points", - 1, - std::bind(&PointcloudObjects::pointcloudCallback, this, std::placeholders::_1)); + "/kinect2/sd/points", + 1, + std::bind(&PointcloudObjects::pointcloudCallback, this, std::placeholders::_1) + ); } private: @@ -127,11 +127,12 @@ private: float object_z = points_z_sum/point_num; RCLCPP_INFO( this->get_logger(), - "object %d pos = ( %.2f , %.2f , %.2f)" , + "object %d pos=(%.2f , %.2f , %.2f)", i, object_x, object_y, - object_z); + object_z + ); } RCLCPP_INFO(this->get_logger(), "---------------------" ); }