Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Dec 22, 2023
1 parent 7d3b5e1 commit 8e1b93d
Show file tree
Hide file tree
Showing 20 changed files with 81 additions and 75 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,8 @@
/// \file
/// \brief Common functionality for bounding box computation algorithms

#ifndef GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_
#define GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_

#include "autoware_auto_geometry/common_2d.hpp>
#include "autoware_auto_geometry/visibility_control.hpp>
#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_
#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_

#include <autoware_auto_perception_msgs/msg/bounding_box.hpp>
#include <autoware_auto_perception_msgs/msg/detected_object.hpp>
Expand All @@ -32,6 +29,9 @@
#include <limits>
#include <vector>

#include "autoware_auto_geometry/common_2d.hpp>
#include "autoware_auto_geometry/visibility_control.hpp>

namespace autoware
{
namespace common
Expand Down Expand Up @@ -185,4 +185,4 @@ std::vector<geometry_msgs::msg::Point32> GEOMETRY_PUBLIC get_transformed_corners
} // namespace common
} // namespace autoware

#endif // GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -19,14 +19,14 @@
/// bounding box

// cspell: ignore eigenbox, EIGENBOX
#ifndef GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_
#define GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_

#include "autoware_auto_geometry/bounding_box/bounding_box_common.hpp>
#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_
#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_

#include <limits>
#include <utility>

#include "autoware_auto_geometry/bounding_box/bounding_box_common.hpp>
namespace autoware
{
namespace common
Expand Down Expand Up @@ -244,4 +244,4 @@ BoundingBox eigenbox_2d(const IT begin, const IT end)
} // namespace common
} // namespace autoware
#endif // GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -20,14 +20,14 @@

// cspell: ignore LFIT, lfit
// LFIT means "L-Shape Fitting"
#ifndef GEOMETRY__BOUNDING_BOX__LFIT_HPP_
#define GEOMETRY__BOUNDING_BOX__LFIT_HPP_

#include "autoware_auto_geometry/bounding_box/eigenbox_2d.hpp>
#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__LFIT_HPP_
#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__LFIT_HPP_

#include <limits>
#include <utility>

#include "autoware_auto_geometry/bounding_box/eigenbox_2d.hpp>
namespace autoware
{
namespace common
Expand Down Expand Up @@ -278,4 +278,4 @@ BoundingBox lfit_bounding_box_2d(const IT begin, const IT end)
} // namespace common
} // namespace autoware
#endif // GEOMETRY__BOUNDING_BOX__LFIT_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__LFIT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -17,17 +17,17 @@
/// \file
/// \brief This file implements the rotating calipers algorithm for minimum oriented bounding boxes

#ifndef GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_
#define GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_
#include "autoware_auto_geometry/bounding_box/bounding_box_common.hpp>
#include "autoware_auto_geometry/common_2d.hpp>
#include "autoware_auto_geometry/convex_hull.hpp>
#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_
#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_
#include <algorithm>
#include <cstring>
#include <limits>
#include <list>

#include "autoware_auto_geometry/bounding_box/bounding_box_common.hpp>
#include "autoware_auto_geometry/common_2d.hpp>
#include "autoware_auto_geometry/convex_hull.hpp>
namespace autoware
{
namespace common
Expand Down Expand Up @@ -277,4 +277,4 @@ BoundingBox minimum_perimeter_bounding_box(std::list<PointT> & list)
} // namespace geometry
} // namespace common
} // namespace autoware
#endif // GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
// Co-developed by Tier IV, Inc. and Apex.AI, Inc.
/// \file
/// \brief Main header for user-facing bounding box algorithms: functions and types
#ifndef GEOMETRY__BOUNDING_BOX_2D_HPP_
#define GEOMETRY__BOUNDING_BOX_2D_HPP_
#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX_2D_HPP_
#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX_2D_HPP_

#include "autoware_auto_geometry/bounding_box/eigenbox_2d.hpp>
#include "autoware_auto_geometry/bounding_box/lfit.hpp>
Expand All @@ -31,4 +31,4 @@ namespace geometry
} // namespace geometry
} // namespace common
} // namespace autoware
#endif // GEOMETRY__BOUNDING_BOX_2D_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX_2D_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
/// \file
/// \brief This file includes common functionality for 2D geometry, such as dot products

#ifndef GEOMETRY__COMMON_2D_HPP_
#define GEOMETRY__COMMON_2D_HPP_
#ifndef AUTOWARE_AUTO_GEOMETRY__COMMON_2D_HPP_
#define AUTOWARE_AUTO_GEOMETRY__COMMON_2D_HPP_

#include "autoware_auto_geometry/interval.hpp"

Expand Down Expand Up @@ -584,4 +584,4 @@ bool is_point_inside_polygon_2d(
} // namespace common
} // namespace autoware

#endif // GEOMETRY__COMMON_2D_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__COMMON_2D_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
/// \file
/// \brief This file includes common functionality for 3D geometry, such as dot products

#ifndef GEOMETRY__COMMON_3D_HPP_
#define GEOMETRY__COMMON_3D_HPP_
#ifndef AUTOWARE_AUTO_GEOMETRY__COMMON_3D_HPP_
#define AUTOWARE_AUTO_GEOMETRY__COMMON_3D_HPP_

#include "autoware_auto_geometry/common_2d.hpp>
Expand Down Expand Up @@ -74,4 +74,4 @@ inline OUT distance_3d(const T1 & a, const T2 & b)
} // namespace common
} // namespace autoware
#endif // GEOMETRY__COMMON_3D_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__COMMON_3D_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,11 @@
/// \brief This file implements the monotone chain algorithm to compute 2D convex hulls on linked
/// lists of points

#ifndef GEOMETRY__CONVEX_HULL_HPP_
#define GEOMETRY__CONVEX_HULL_HPP_
#ifndef AUTOWARE_AUTO_GEOMETRY__CONVEX_HULL_HPP_
#define AUTOWARE_AUTO_GEOMETRY__CONVEX_HULL_HPP_

#include <common/types.hpp>

#include "autoware_auto_geometry/common_2d.hpp>
// lint -e537 NOLINT pclint vs cpplint
Expand Down Expand Up @@ -191,4 +192,4 @@ typename std::list<PointT>::const_iterator convex_hull(std::list<PointT> & list)
} // namespace common
} // namespace autoware
#endif // GEOMETRY__CONVEX_HULL_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__CONVEX_HULL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -18,18 +18,19 @@
/// \brief This file implements an algorithm for getting a list of "pockets" in the convex
/// hull of a non-convex simple polygon.

#ifndef GEOMETRY__HULL_POCKETS_HPP_
#define GEOMETRY__HULL_POCKETS_HPP_
#ifndef AUTOWARE_AUTO_GEOMETRY__HULL_POCKETS_HPP_
#define AUTOWARE_AUTO_GEOMETRY__HULL_POCKETS_HPP_

#include <common/types.hpp>
#include "autoware_auto_geometry/common_2d.hpp>

#include <algorithm>
#include <iterator>
#include <limits>
#include <utility>
#include <vector>

#include "autoware_auto_geometry/common_2d.hpp>
using autoware::common::types::float32_t;
namespace autoware
Expand Down Expand Up @@ -107,4 +108,4 @@ typename std::vector<std::vector<typename std::iterator_traits<Iter1>::value_typ
} // namespace common
} // namespace autoware
#endif // GEOMETRY__HULL_POCKETS_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__HULL_POCKETS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,8 @@
//
// Co-developed by Tier IV, Inc. and Apex.AI, Inc.

#ifndef GEOMETRY__INTERSECTION_HPP_
#define GEOMETRY__INTERSECTION_HPP_

#include "autoware_auto_geometry/common_2d.hpp>
#include "autoware_auto_geometry/convex_hull.hpp>
#ifndef AUTOWARE_AUTO_GEOMETRY__INTERSECTION_HPP_
#define AUTOWARE_AUTO_GEOMETRY__INTERSECTION_HPP_

#include <autoware_auto_perception_msgs/msg/bounding_box.hpp>
#include <autoware_auto_planning_msgs/msg/trajectory_point.hpp>
Expand All @@ -32,6 +29,9 @@
#include <utility>
#include <vector>

#include "autoware_auto_geometry/common_2d.hpp>
#include "autoware_auto_geometry/convex_hull.hpp>

namespace autoware
{
namespace common
Expand Down Expand Up @@ -309,4 +309,4 @@ common::types::float32_t convex_intersection_over_union_2d(
} // namespace common
} // namespace autoware

#endif // GEOMETRY__INTERSECTION_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__INTERSECTION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@
// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
// IN THE SOFTWARE.

#ifndef GEOMETRY__INTERVAL_HPP_
#define GEOMETRY__INTERVAL_HPP_
#ifndef AUTOWARE_AUTO_GEOMETRY__INTERVAL_HPP_
#define AUTOWARE_AUTO_GEOMETRY__INTERVAL_HPP_

#include "common/types.hpp"
#include "helper_functions/float_comparisons.hpp"
Expand Down Expand Up @@ -355,4 +355,4 @@ T Interval<T>::clamp_to(const Interval & i, T val)
} // namespace common
} // namespace autoware

#endif // GEOMETRY__INTERVAL_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__INTERVAL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,11 @@
/// \file
/// \brief This file contains a 1D linear lookup table implementation

#ifndef GEOMETRY__LOOKUP_TABLE_HPP_
#define GEOMETRY__LOOKUP_TABLE_HPP_
#ifndef AUTOWARE_AUTO_GEOMETRY__LOOKUP_TABLE_HPP_
#define AUTOWARE_AUTO_GEOMETRY__LOOKUP_TABLE_HPP_

#include "common/types.hpp"
#include "autoware_auto_geometry/interval.hpp"
#include "common/types.hpp"

#include <cmath>
#include <stdexcept>
Expand Down Expand Up @@ -175,4 +175,4 @@ class LookupTable1D
} // namespace common
} // namespace autoware

#endif // GEOMETRY__LOOKUP_TABLE_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__LOOKUP_TABLE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -17,17 +17,18 @@
/// \brief This file implements a spatial hash for efficient fixed-radius near neighbor queries in
/// 2D

#ifndef GEOMETRY__SPATIAL_HASH_HPP_
#define GEOMETRY__SPATIAL_HASH_HPP_
#ifndef AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_HPP_
#define AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_HPP_

#include <common/types.hpp>
#include "autoware_auto_geometry/spatial_hash_config.hpp>
#include "autoware_auto_geometry/visibility_control.hpp>

#include <unordered_map>
#include <utility>
#include <vector>

#include "autoware_auto_geometry/spatial_hash_config.hpp>
#include "autoware_auto_geometry/visibility_control.hpp>

using autoware::common::types::bool8_t;
using autoware::common::types::float32_t;

Expand Down Expand Up @@ -328,4 +329,4 @@ using SpatialHash3d = SpatialHash<T, Config3d>;
} // namespace common
} // namespace autoware

#endif // GEOMETRY__SPATIAL_HASH_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -17,21 +17,22 @@
/// \brief This file implements a spatial hash for efficient fixed-radius near neighbor queries in
/// 2D

#ifndef GEOMETRY__SPATIAL_HASH_CONFIG_HPP_
#define GEOMETRY__SPATIAL_HASH_CONFIG_HPP_
#ifndef AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_CONFIG_HPP_
#define AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_CONFIG_HPP_

#include "helper_functions/crtp.hpp"

#include <common/types.hpp>
#include "autoware_auto_geometry/common_2d.hpp>
#include "autoware_auto_geometry/visibility_control.hpp>

#include <algorithm>
#include <cmath>
#include <limits>
#include <stdexcept>
#include <utility>

#include "autoware_auto_geometry/common_2d.hpp>
#include "autoware_auto_geometry/visibility_control.hpp>

using autoware::common::types::bool8_t;
using autoware::common::types::float32_t;
using autoware::common::types::float64_t;
Expand Down Expand Up @@ -447,4 +448,4 @@ class GEOMETRY_PUBLIC Config3d : public Config<Config3d>
} // namespace common
} // namespace autoware

#endif // GEOMETRY__SPATIAL_HASH_CONFIG_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_CONFIG_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
//
// Co-developed by Tier IV, Inc. and Apex.AI, Inc.

#ifndef GEOMETRY__VISIBILITY_CONTROL_HPP_
#define GEOMETRY__VISIBILITY_CONTROL_HPP_
#ifndef AUTOWARE_AUTO_GEOMETRY__VISIBILITY_CONTROL_HPP_
#define AUTOWARE_AUTO_GEOMETRY__VISIBILITY_CONTROL_HPP_

////////////////////////////////////////////////////////////////////////////////
#if defined(__WIN32)
Expand All @@ -38,4 +38,4 @@
#else // defined(__linux__)
#error "Unsupported Build Configuration"
#endif // defined(__WIN32)
#endif // GEOMETRY__VISIBILITY_CONTROL_HPP_
#endif // AUTOWARE_AUTO_GEOMETRY__VISIBILITY_CONTROL_HPP_
5 changes: 3 additions & 2 deletions common/autoware_auto_geometry/src/bounding_box.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,13 +15,12 @@
// Co-developed by Tier IV, Inc. and Apex.AI, Inc.

#include <autoware_auto_tf2/tf2_autoware_auto_msgs.hpp>

#include "autoware_auto_geometry/bounding_box/bounding_box_common.hpp>
#include "autoware_auto_geometry/bounding_box/eigenbox_2d.hpp>
// cspell: ignore eigenbox
#include "autoware_auto_geometry/bounding_box/lfit.hpp>
// cspell: ignore lfit
#include "autoware_auto_geometry/bounding_box/rotating_calipers.hpp>

#include <geometry_msgs/msg/point32.hpp>
#include <algorithm>
Expand All @@ -30,6 +29,8 @@
#include <utility>
#include <vector>
#include "autoware_auto_geometry/bounding_box/rotating_calipers.hpp>

namespace autoware
{
namespace common
Expand Down
3 changes: 2 additions & 1 deletion common/autoware_auto_geometry/test/src/lookup_table.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,10 @@
//
// Co-developed by Tier IV, Inc. and Apex.AI, Inc.

#include <common/types.hpp>
#include "autoware_auto_geometry/lookup_table.hpp>
#include <common/types.hpp>
#include <gtest/gtest.h>
#include <memory>
Expand Down
Loading

0 comments on commit 8e1b93d

Please sign in to comment.