Go to the documentation of this file.
17 #ifndef TRACKING__PROJECTION_HPP_
18 #define TRACKING__PROJECTION_HPP_
20 #include <autoware_auto_perception_msgs/msg/shape.hpp>
22 #include <geometry_msgs/msg/polygon.hpp>
23 #include <geometry_msgs/msg/transform.hpp>
26 #include <Eigen/Geometry>
28 #include <experimental/optional>
42 using Point = geometry_msgs::msg::Point32;
43 std::list<Point> shape{};
49 std::size_t width{0U};
50 std::size_t height{0U};
65 using Point = geometry_msgs::msg::Point32;
81 std::experimental::optional<Projection>
82 project(
const std::vector<Point> & points)
const;
87 std::experimental::optional<EigPoint> project_point(
const EigPoint & pt_3d)
const;
89 Eigen::Matrix3f m_intrinsics;
92 std::list<Point> m_corners;
100 #endif // TRACKING__PROJECTION_HPP_
This file implements the monotone chain algorithm to compute 2D convex hulls on linked lists of point...
This file includes common type definition.
Camera intrinsic parameters.
Definition: projection.hpp:47
This file includes common functionality for 2D geometry, such as dot products.
Eigen::Vector3f EigPoint
Definition: projection.hpp:66
geometry_msgs::msg::Point32 Point
Definition: projection.hpp:42
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
Definition: projection.hpp:40
This model represents a camera in 3D space and can project 3D shapes into an image.
Definition: projection.hpp:60
float float32_t
Definition: types.hpp:45
common::types::float32_t float32_t
Definition: projection.hpp:63
Eigen::Matrix< float64_t, 3, 1 > Vector3f
Definition: trajectory_common.hpp:42
geometry_msgs::msg::Point32 Point
Definition: projection.hpp:65