Skip to content

Commit

Permalink
fix(cpplint): include what you use - sensing (#9571)
Browse files Browse the repository at this point in the history
Signed-off-by: M. Fatih Cırıt <[email protected]>
  • Loading branch information
xmfcx authored Dec 4, 2024
1 parent 1e5077c commit cbe13bf
Show file tree
Hide file tree
Showing 21 changed files with 47 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include <std_msgs/msg/header.hpp>

#include <string>
#include <vector>

namespace autoware::image_diagnostics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@
#include <autoware/universe_utils/geometry/geometry.hpp>
#include <rclcpp/rclcpp.hpp>

#include <vector>

namespace autoware::imu_corrector
{

Expand Down
2 changes: 2 additions & 0 deletions sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,9 @@
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

#include <memory>
#include <utility>
#include <vector>

namespace autoware::imu_corrector
{
Expand Down
3 changes: 3 additions & 0 deletions sensing/autoware_imu_corrector/src/imu_corrector_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,9 @@

#include "imu_corrector_core.hpp"

#include <memory>
#include <string>

#ifdef ROS_DISTRO_GALACTIC
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#else
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@

#include <gtest/gtest.h>

#include <vector>

namespace autoware::imu_corrector
{
class GyroBiasEstimationModuleTest : public ::testing::Test
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@

#include <algorithm>
#include <numeric>
#include <string>
#include <vector>

namespace autoware::pointcloud_preprocessor
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@
#include <pcl_conversions/pcl_conversions.h>

#include <algorithm>
#include <map>
#include <memory>
#include <string>
#include <utility>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@

#include <sensor_msgs/point_cloud2_iterator.hpp>

#include <memory>
#include <vector>

namespace autoware::pointcloud_preprocessor
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,10 @@
#include <autoware/universe_utils/math/trigonometry.hpp>
#include <tf2_eigen/tf2_eigen.hpp>

#include <deque>
#include <memory>
#include <string>

namespace autoware::pointcloud_preprocessor
{

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,10 @@

#include "autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp"

#include <memory>
#include <string>
#include <utility>

namespace autoware::pointcloud_preprocessor
{
/** @brief Constructor. */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include "autoware/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp"

#include <cfloat>
#include <unordered_map>

namespace autoware::pointcloud_preprocessor
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,9 @@

#include "robin_hood.h"

#include <memory>
#include <vector>

namespace
{
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@
#include <string>
#include <type_traits>
#include <utility>
#include <tuple>
#if __cplusplus >= 201703L
#include <string_view>
#endif
Expand All @@ -85,7 +86,7 @@
#ifdef ROBIN_HOOD_TRACE_ENABLED
#include <iostream>
#define ROBIN_HOOD_TRACE(...) \
std::cout << __FUNCTION__ << "@" << __LINE__ << ": " << __VA_ARGS__ << std::endl;
std::cout << __FUNCTION__ << "@" << __LINE__ << ": " << __VA_ARGS__ << std::endl; // NOLINT
#else
#define ROBIN_HOOD_TRACE(x)
#endif
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@
#include <sensor_msgs/point_cloud2_iterator.hpp>

#include <algorithm>
#include <memory>
#include <utility>
#include <vector>
namespace autoware::pointcloud_preprocessor
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "autoware/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp"

#include <memory>

namespace autoware::pointcloud_preprocessor
{
PolygonRemoverComponent::PolygonRemoverComponent(const rclcpp::NodeOptions & options)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
#include <pcl_conversions/pcl_conversions.h>

#include <algorithm>
#include <map>
#include <memory>
#include <string>
#include <utility>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "autoware/pointcloud_preprocessor/utility/geometry.hpp"

#include <vector>

namespace autoware::pointcloud_preprocessor::utils
{
void to_cgal_polygon(const geometry_msgs::msg::Polygon & polygon_in, PolygonCgal & polygon_out)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,10 @@

#include "autoware/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter_node.hpp"

#include <memory>
#include <string>
#include <vector>

namespace
{
autoware::universe_utils::Box2d calcBoundingBox(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,10 @@
#include <tf2_ros/static_transform_broadcaster.h>

#include <cassert>
#include <memory>
#include <string>
#include <tuple>
#include <vector>

enum AngleCoordinateSystem { HESAI, VELODYNE, CARTESIAN };
class DistortionCorrectorTest : public ::testing::Test
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@

#include <gtest/gtest.h>

#include <memory>

std::shared_ptr<autoware::radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode> get_node(
float velocity_y_threshold)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "vehicle_velocity_converter/vehicle_velocity_converter.hpp"

#include <string>

VehicleVelocityConverter::VehicleVelocityConverter(const rclcpp::NodeOptions & options)
: rclcpp::Node("vehicle_velocity_converter", options)
{
Expand Down

0 comments on commit cbe13bf

Please sign in to comment.