Autoware.Auto
shapes.hpp
Go to the documentation of this file.
1 // Copyright 2021 The Autoware Foundation
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 
19 
20 #ifndef TRACKING_TEST_FRAMEWORK__SHAPES_HPP_
21 #define TRACKING_TEST_FRAMEWORK__SHAPES_HPP_
22 
25 
26 #include <common/types.hpp>
27 
28 #include <Eigen/Core>
29 #include <Eigen/Geometry>
30 
31 #include <cstdint>
32 #include <memory>
33 #include <vector>
34 
35 namespace autoware
36 {
37 namespace tracking_test_framework
38 {
39 
41 class TRACKING_TEST_FRAMEWORK_PUBLIC Line;
42 
43 
45 class TRACKING_TEST_FRAMEWORK_PUBLIC Shape
46 {
47 public:
53  virtual EigenStlVector<Eigen::Vector2f> intersect_with_line(
54  const Line & line, const autoware::common::types::bool8_t closest_point_only) const = 0;
55 
57  virtual ~Shape() = default;
58 };
59 
62 class TRACKING_TEST_FRAMEWORK_PUBLIC Line : public Shape
63 {
64 public:
66  Line() = default;
67 
69  Line(const Eigen::Vector2f & start, const Eigen::Vector2f & end);
70 
76  EigenStlVector<Eigen::Vector2f> intersect_with_line(
77  const Line & line, const autoware::common::types::bool8_t closest_point_only) const override;
78 
86  Eigen::Vector2f get_point(const autoware::common::types::float32_t scale) const;
87 
90  inline const Eigen::Vector2f & starting_point() const
91  {
92  return m_start;
93  }
94 
97  inline const Eigen::Vector2f & end_point() const
98  {
99  return m_end;
100  }
101 
104  inline const Eigen::Vector2f & direction() const
105  {
106  return m_line_direction;
107  }
108 
112  {
113  return m_line_length;
114  }
115 
116 private:
118  Eigen::Vector2f m_start{Eigen::Vector2f::Zero()};
120  Eigen::Vector2f m_end{Eigen::Vector2f::Zero()};
122  autoware::common::types::float32_t m_line_length{};
124  Eigen::Vector2f m_line_direction{Eigen::Vector2f::Zero()};
125 };
126 
129 class TRACKING_TEST_FRAMEWORK_PUBLIC Rectangle : public Shape
130 {
131 public:
133  Rectangle(
134  const Eigen::Vector2f & center, const Eigen::Vector2f & size,
135  const autoware::common::types::float32_t orientation_degrees);
136 
142  EigenStlVector<Eigen::Vector2f> intersect_with_line(
143  const Line & line, const autoware::common::types::bool8_t closest_point_only) const override;
144 
145 private:
147  Eigen::Vector2f m_center{Eigen::Vector2f::Zero()};
149  Eigen::Vector2f m_size{Eigen::Vector2f::Zero()};
151  autoware::common::types::float32_t m_orientation_radians{};
153  std::array<Line, 4> m_borders{};
155  std::array<Eigen::Vector2f, 4> m_corners{};
156 };
157 
160 class TRACKING_TEST_FRAMEWORK_PUBLIC Circle : public Shape
161 {
162 public:
164  Circle(const Eigen::Vector2f & center, const autoware::common::types::float32_t radius);
165 
171  EigenStlVector<Eigen::Vector2f> intersect_with_line(
172  const Line & line, const autoware::common::types::bool8_t closest_point_only) const override;
173 
174 private:
176  Eigen::Vector2f m_center{Eigen::Vector2f::Zero()};
179 };
180 
181 } // namespace tracking_test_framework
182 } // namespace autoware
183 #endif // TRACKING_TEST_FRAMEWORK__SHAPES_HPP_
class TRACKING_TEST_FRAMEWORK_PUBLIC Line
Forward declaration of the Line class.
Definition: shapes.hpp:41
This is the class which represents the pedestrians as circles in 2D and defines the function intersec...
Definition: shapes.hpp:160
This is the class which represents the line and defines the function intersect_with_line which gives ...
Definition: shapes.hpp:62
float float32_t
Definition: types.hpp:36
This is the base class for the 2D shapes.
Definition: shapes.hpp:45
bool bool8_t
Definition: types.hpp:33
const Eigen::Vector2f & end_point() const
gets the end point of the line
Definition: shapes.hpp:97
This file includes common type definition.
const Eigen::Vector2f & direction() const
gets the line direction
Definition: shapes.hpp:104
const autoware::common::types::float32_t & length() const
gets the line length
Definition: shapes.hpp:111
const Eigen::Vector2f & starting_point() const
gets the starting point of the line
Definition: shapes.hpp:90
end
Definition: scripts/get_open_port.py:23
This is the class which represents the cars as rectangles in 2D and defines the function intersect_wi...
Definition: shapes.hpp:129
std::vector< EigenVectorT, Eigen::aligned_allocator< EigenVectorT > > EigenStlVector
Definition: eigen_stl_vector.hpp:28
This file contains the typedef for using fixed size EigenVectors with std::vector due to issues docum...
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24