Optimize includes (#407)
This commit is contained in:
parent
1e544f132e
commit
6642b7398a
@ -40,7 +40,6 @@
|
|||||||
|
|
||||||
// PCL includes
|
// PCL includes
|
||||||
#include <pcl/filters/extract_indices.h>
|
#include <pcl/filters/extract_indices.h>
|
||||||
#include <mutex>
|
|
||||||
#include <vector>
|
#include <vector>
|
||||||
#include "pcl_ros/filters/filter.hpp"
|
#include "pcl_ros/filters/filter.hpp"
|
||||||
|
|
||||||
|
|||||||
@ -38,7 +38,6 @@
|
|||||||
#ifndef PCL_ROS__FILTERS__FILTER_HPP_
|
#ifndef PCL_ROS__FILTERS__FILTER_HPP_
|
||||||
#define PCL_ROS__FILTERS__FILTER_HPP_
|
#define PCL_ROS__FILTERS__FILTER_HPP_
|
||||||
|
|
||||||
#include <pcl/filters/filter.h>
|
|
||||||
#include <memory>
|
#include <memory>
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|||||||
@ -47,7 +47,8 @@
|
|||||||
#include <tf2_ros/buffer.h>
|
#include <tf2_ros/buffer.h>
|
||||||
#include <tf2_ros/transform_listener.h>
|
#include <tf2_ros/transform_listener.h>
|
||||||
|
|
||||||
#include <Eigen/Dense>
|
#include <Eigen/Core>
|
||||||
|
#include <Eigen/Geometry>
|
||||||
#include <string>
|
#include <string>
|
||||||
|
|
||||||
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
|
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
|
||||||
|
|||||||
@ -37,11 +37,11 @@
|
|||||||
#ifndef PCL_ROS__TRANSFORMS_HPP_
|
#ifndef PCL_ROS__TRANSFORMS_HPP_
|
||||||
#define PCL_ROS__TRANSFORMS_HPP_
|
#define PCL_ROS__TRANSFORMS_HPP_
|
||||||
|
|
||||||
#include <pcl/common/transforms.h>
|
#include <pcl/point_cloud.h>
|
||||||
#include <tf2/LinearMath/Transform.h>
|
#include <tf2/LinearMath/Transform.h>
|
||||||
#include <tf2_ros/buffer.h>
|
#include <tf2_ros/buffer.h>
|
||||||
#include <tf2_ros/transform_listener.h>
|
#include <tf2_ros/transform_listener.h>
|
||||||
#include <Eigen/Dense>
|
#include <Eigen/Core>
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <rclcpp/time.hpp>
|
#include <rclcpp/time.hpp>
|
||||||
#include <sensor_msgs/msg/point_cloud2.hpp>
|
#include <sensor_msgs/msg/point_cloud2.hpp>
|
||||||
|
|||||||
@ -36,7 +36,6 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include "pcl_ros/filters/project_inliers.hpp"
|
#include "pcl_ros/filters/project_inliers.hpp"
|
||||||
#include <pcl/io/io.h>
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////////////////////
|
||||||
pcl_ros::ProjectInliers::ProjectInliers(const rclcpp::NodeOptions & options)
|
pcl_ros::ProjectInliers::ProjectInliers(const rclcpp::NodeOptions & options)
|
||||||
|
|||||||
@ -47,7 +47,7 @@
|
|||||||
#include <tf2_ros/buffer.h>
|
#include <tf2_ros/buffer.h>
|
||||||
#include <tf2_ros/transform_listener.h>
|
#include <tf2_ros/transform_listener.h>
|
||||||
|
|
||||||
#include <Eigen/Dense>
|
#include <Eigen/Core>
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
#include <limits>
|
#include <limits>
|
||||||
#include <string>
|
#include <string>
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user