Skip to content

Commit 9f921ec

Browse files
mats4cassava
authored andcommitted
plugins/frustum_culling: Add frustum culling as a cloe plugin.
1 parent 27dbc38 commit 9f921ec

15 files changed

+1450
-0
lines changed

conanfile.py

+1
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@ def cloe_requires(dep):
4646
cloe_requires("cloe-models")
4747
cloe_requires("cloe-plugin-basic")
4848
cloe_requires("cloe-plugin-clothoid-fit")
49+
cloe_requires("cloe-plugin-frustum-culling")
4950
cloe_requires("cloe-plugin-gndtruth-extractor")
5051
cloe_requires("cloe-plugin-minimator")
5152
cloe_requires("cloe-plugin-mocks")

models/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,7 @@ if(BUILD_TESTING)
5656
src/cloe/component/latlong_actuator_test.cpp
5757
src/cloe/component/utility/steering_utils_test.cpp
5858
src/cloe/utility/actuation_level_test.cpp
59+
src/cloe/utility/frustum_culling_test.cpp
5960
)
6061
set_target_properties(test-models PROPERTIES
6162
CXX_STANDARD 17
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,151 @@
1+
/*
2+
* Copyright 2024 Robert Bosch GmbH
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*
16+
* SPDX-License-Identifier: Apache-2.0
17+
*/
18+
/**
19+
* \file cloe/utility/frustum_culling.hpp
20+
*/
21+
22+
#pragma once
23+
24+
#include <cmath> // for cos, sin
25+
26+
#include <fmt/format.h> // for format
27+
#include <Eigen/Geometry> // for Vector3d
28+
#include <cloe/component/frustum.hpp> // for Frustum
29+
30+
namespace cloe::utility {
31+
32+
struct Point {
33+
double x{0.0};
34+
double y{0.0};
35+
};
36+
37+
// Rotates a given point from one coordinate system to another and returns rotated point
38+
Point rotate_point(const Point& point, double angle) {
39+
return Point{std::cos(angle) * point.x - std::sin(angle) * point.y,
40+
std::sin(angle) * point.x + std::cos(angle) * point.y};
41+
}
42+
43+
// Calculates the corner points of a field of view.
44+
// p0 to p2 are the points counter clock-wise with the idstance clip_far to the root
45+
// An additional offset of the field of view to the original coordinate coordinate system is considered.
46+
//
47+
// clip_far p2 p1
48+
// \ /
49+
// x \ /
50+
// ^ \ /
51+
// | \ /
52+
// y <---| \ /
53+
// p0
54+
// \param fov Angle [radians] between p0-p1 and p0-p2
55+
// \param offset Angle [radians] to shift the points p1 and p2 by
56+
// \param clip_far Distance [meters] from p0 to p1 and from p0 to p2
57+
//
58+
// \return Vector of points p0, p1, p2.
59+
std::vector<Point> calc_corner_points(double fov, double offset, double clip_far) {
60+
std::vector<Point> ret_points;
61+
62+
// initialize points
63+
Point p0{0.0, 0.0};
64+
Point p1{p0};
65+
Point p2{p0};
66+
67+
ret_points.push_back(p0);
68+
69+
p1.x = clip_far * std::cos(-fov / 2.0);
70+
p2.x = clip_far * std::cos(fov / 2.0);
71+
72+
p1.y = clip_far * std::sin(-fov / 2.0);
73+
p2.y = clip_far * std::sin(fov / 2.0);
74+
75+
p1 = rotate_point(p1, offset);
76+
p2 = rotate_point(p2, offset);
77+
78+
ret_points.push_back(p1);
79+
ret_points.push_back(p2);
80+
81+
return ret_points;
82+
}
83+
84+
// Returns true if a given Point c is "on the left" of the line of two points a and b.
85+
// "On the left" means the angle from the line a-b to the line a-c is in the range (0, M_PI)
86+
bool is_left(Point a, Point b, Point c) {
87+
return (b.x - a.x) * (c.y - a.y) - (b.y - a.y) * (c.x - a.x) > 0;
88+
}
89+
90+
bool is_inside_fov(double fov, bool is_left_0_p1, bool is_left_0_p2, std::string error_message) {
91+
bool is_inside_fov = false;
92+
if (fov >= M_PI && fov <= 2 * M_PI) {
93+
// if the opening angle is between PI and 2 PI (180 and 360 degree)
94+
// then everything is inside the fov that is _not_ right of p1 AND is _not_ left of p2
95+
is_inside_fov = !(!is_left_0_p1 && is_left_0_p2);
96+
} else if (fov > 0.0 && fov < M_PI) {
97+
// if the opening angle is greater 0 and smaller than M_PI
98+
is_inside_fov = is_left_0_p1 && !is_left_0_p2;
99+
} else {
100+
throw std::runtime_error(error_message);
101+
}
102+
return is_inside_fov;
103+
}
104+
105+
bool is_point_inside_frustum(const cloe::Frustum& frustum, const Eigen::Vector3d& point) {
106+
bool ret_val{false};
107+
108+
// calculate points in "frustum" sensor coordinate system, which starts at the frustum root
109+
// and has x in viewing direction, and y to the left and z in the up direction.
110+
auto corner_points_x_y_plane =
111+
calc_corner_points(frustum.fov_h, frustum.offset_h, frustum.clip_far);
112+
auto corner_points_x_z_plane =
113+
calc_corner_points(frustum.fov_v, frustum.offset_v, frustum.clip_far);
114+
115+
// calculate for xy plane
116+
bool is_left_0_p1 =
117+
is_left(corner_points_x_y_plane[0], corner_points_x_y_plane[1], Point{point.x(), point.y()});
118+
bool is_left_0_p2 =
119+
is_left(corner_points_x_y_plane[0], corner_points_x_y_plane[2], Point{point.x(), point.y()});
120+
121+
bool is_inside_fov_xy =
122+
is_inside_fov(frustum.fov_h, is_left_0_p1, is_left_0_p2,
123+
fmt::format("The field of view in horizontal direction of your function is not "
124+
"in the expected range of (0, 2*PI]. The value we got was {}",
125+
frustum.fov_h));
126+
127+
// now calculate for xz plane
128+
is_left_0_p1 =
129+
is_left(corner_points_x_z_plane[0], corner_points_x_z_plane[1], Point{point.z(), point.x()});
130+
is_left_0_p2 =
131+
is_left(corner_points_x_z_plane[0], corner_points_x_z_plane[2], Point{point.z(), point.x()});
132+
133+
bool is_inside_fov_xz =
134+
is_inside_fov(frustum.fov_v, is_left_0_p1, is_left_0_p2,
135+
fmt::format("The field of view in vertical direction of your function is not "
136+
"in the expected range of (0, 2*PI]. The value we got was {}",
137+
frustum.fov_v));
138+
139+
// if we are inside the fovs, we still need to check if the distance is within clip_near and clip_far
140+
if (is_inside_fov_xy && is_inside_fov_xz) {
141+
double distance =
142+
std::sqrt(std::pow(point.x(), 2) + std::pow(point.y(), 2) + std::pow(point.z(), 2));
143+
144+
if (distance >= frustum.clip_near && distance < frustum.clip_far) {
145+
ret_val = true;
146+
}
147+
}
148+
return ret_val;
149+
}
150+
151+
} // namespace cloe::utility

0 commit comments

Comments
 (0)