Skip to content
Open
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions pcl_ros/include/pcl_ros/impl/transforms.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,8 @@

#include <pcl/common/transforms.h>
#include <pcl_conversions/pcl_conversions.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.hpp>
#include <tf2_ros/transform_listener.hpp>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think cpplint now fails because now the .hpp include should go with the other .hpp includes

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hmm, guess you're right. If only we had tools with a --reformat option 😄


#include <Eigen/Core>
#include <Eigen/Geometry>
Expand Down
4 changes: 2 additions & 2 deletions pcl_ros/include/pcl_ros/pcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,8 @@
#include <pcl/pcl_base.h>
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.hpp>
#include <tf2_ros/buffer.hpp>

#include <memory>
#include <string>
Expand Down
4 changes: 2 additions & 2 deletions pcl_ros/include/pcl_ros/transforms.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@
#define PCL_ROS__TRANSFORMS_HPP_

#include <pcl/point_cloud.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.hpp>
#include <tf2_ros/transform_listener.hpp>

#include <Eigen/Core>
#include <string>
Expand Down
4 changes: 2 additions & 2 deletions pcl_ros/src/transforms.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,8 @@
#include <pcl/common/transforms.h>
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.hpp>
#include <tf2_ros/transform_listener.hpp>

#include <Eigen/Core>
#include <cmath>
Expand Down
4 changes: 2 additions & 2 deletions pcl_ros/tools/pointcloud_to_pcd.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,8 @@ Cloud Data) file format.
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.hpp>
#include <tf2_ros/transform_listener.hpp>

#include <pcl_ros/transforms.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down