Autoware.Auto
projection.hpp
Go to the documentation of this file.
1 // Copyright 2021 Apex.AI, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
17 #ifndef TRACKING__PROJECTION_HPP_
18 #define TRACKING__PROJECTION_HPP_
19 
20 #include <autoware_auto_perception_msgs/msg/shape.hpp>
21 #include <common/types.hpp>
22 #include <geometry_msgs/msg/polygon.hpp>
23 #include <geometry_msgs/msg/transform.hpp>
24 #include <geometry/convex_hull.hpp>
25 #include <geometry/common_2d.hpp>
26 #include <Eigen/Geometry>
27 #include <geometry/interval.hpp>
28 #include <experimental/optional>
30 #include <list>
31 #include <algorithm>
32 #include <vector>
33 
34 namespace autoware
35 {
36 namespace perception
37 {
38 namespace tracking
39 {
40 struct TRACKING_PUBLIC Projection
41 {
42  using Point = geometry_msgs::msg::Point32;
43  std::list<Point> shape{};
44 };
45 
47 struct TRACKING_PUBLIC CameraIntrinsics
48 {
49  std::size_t width{0U};
50  std::size_t height{0U};
51  float32_t fx{0.0F};
52  float32_t fy{0.0F};
53  float32_t ox{0.0F};
54  float32_t oy{0.0F};
55  float32_t skew{0.0F};
56 };
57 
59 // frame.
60 class TRACKING_PUBLIC CameraModel
61 {
62 public:
65  using Point = geometry_msgs::msg::Point32;
67 
70  explicit CameraModel(
71  const CameraIntrinsics & intrinsics
72  );
73 
76  // the image of the camera model. The resulting list of points are then outlined using the
77  // `convex_hull` algorithm and then the outline of points are returned.
81  std::experimental::optional<Projection>
82  project(const std::vector<Point> & points) const;
83 
84 private:
86  // camera)
87  std::experimental::optional<EigPoint> project_point(const EigPoint & pt_3d) const;
88 
89  Eigen::Matrix3f m_intrinsics;
90  Interval m_height_interval;
91  Interval m_width_interval;
92  std::list<Point> m_corners;
93 };
94 
95 } // namespace tracking
96 } // namespace perception
97 } // namespace autoware
98 
99 
100 #endif // TRACKING__PROJECTION_HPP_
convex_hull.hpp
This file implements the monotone chain algorithm to compute 2D convex hulls on linked lists of point...
types.hpp
This file includes common type definition.
autoware::perception::tracking::CameraIntrinsics
Camera intrinsic parameters.
Definition: projection.hpp:47
common_2d.hpp
This file includes common functionality for 2D geometry, such as dot products.
visibility_control.hpp
autoware::perception::tracking::CameraModel::EigPoint
Eigen::Vector3f EigPoint
Definition: projection.hpp:66
autoware::perception::tracking::Projection::Point
geometry_msgs::msg::Point32 Point
Definition: projection.hpp:42
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::perception::tracking::Projection
Definition: projection.hpp:40
autoware::perception::tracking::CameraModel
This model represents a camera in 3D space and can project 3D shapes into an image.
Definition: projection.hpp:60
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
interval.hpp
autoware::perception::tracking::CameraModel::float32_t
common::types::float32_t float32_t
Definition: projection.hpp:63
autoware::motion::motion_common::Vector3f
Eigen::Matrix< float64_t, 3, 1 > Vector3f
Definition: trajectory_common.hpp:42
autoware::common::geometry::Interval< float32_t >
autoware::perception::tracking::CameraModel::Point
geometry_msgs::msg::Point32 Point
Definition: projection.hpp:65