update demo_11

This commit is contained in:
Robot 2023-09-05 19:27:06 +08:00
parent 0ecb1187b5
commit 84a0d2ce0d
3 changed files with 11 additions and 3 deletions

View File

@ -28,7 +28,10 @@ int main(int argc, char **argv)
node = std::make_shared<rclcpp::Node>("pointcloud_data_node");
auto pc_sub = node->create_subscription<sensor_msgs::msg::PointCloud2>(
"/kinect2/sd/points", 1, PointcloudCallback);
"/kinect2/sd/points",
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)).best_effort(),
PointcloudCallback
);
rclcpp::spin(node);

View File

@ -113,7 +113,10 @@ int main(int argc, char **argv)
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
auto pc_sub = node->create_subscription<sensor_msgs::msg::PointCloud2>(
"/kinect2/sd/points", 1, PointcloudCallback);
"/kinect2/sd/points",
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)).best_effort(),
PointcloudCallback
);
rclcpp::spin(node);

View File

@ -20,7 +20,9 @@ public:
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
pc_sub_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"/kinect2/sd/points", 10, std::bind(&PointcloudObjects::pointcloudCallback, this, std::placeholders::_1));
"/kinect2/sd/points",
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)).best_effort(),
std::bind(&PointcloudObjects::pointcloudCallback, this, std::placeholders::_1));
}
private: