Gazebo Math
API Reference
8.0.0
insert_drive_file
Tutorials
library_books
Classes
toc
Namespaces
insert_drive_file
Files
launch
Gazebo Website
Index
List
Hierarchy
Members: All
Members: Functions
Members: Variables
Members: Typedefs
Members: Enumerations
Members: Enumerator
List
Members
Functions
Typedefs
Variables
Enumerations
Enumerator
src
gz-math
include
gz
math
Frustum.hh
Go to the documentation of this file.
1
/*
2
* Copyright (C) 2015 Open Source Robotics Foundation
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
*/
17
#ifndef GZ_MATH_FRUSTUM_HH_
18
#define GZ_MATH_FRUSTUM_HH_
19
20
#include <
gz/math/Angle.hh
>
21
#include <
gz/math/AxisAlignedBox.hh
>
22
#include <
gz/math/Plane.hh
>
23
#include <
gz/math/Pose3.hh
>
24
#include <gz/math/config.hh>
25
#include <gz/utils/ImplPtr.hh>
26
27
namespace
gz::math
28
{
29
// Inline bracket to help doxygen filtering.
30
inline
namespace
GZ_MATH_VERSION_NAMESPACE {
31
34
class
GZ_MATH_VISIBLE
Frustum
35
{
37
public
:
enum
FrustumPlane
38
{
40
FRUSTUM_PLANE_NEAR = 0,
41
43
FRUSTUM_PLANE_FAR = 1,
44
46
FRUSTUM_PLANE_LEFT = 2,
47
49
FRUSTUM_PLANE_RIGHT = 3,
50
52
FRUSTUM_PLANE_TOP = 4,
53
55
FRUSTUM_PLANE_BOTTOM = 5
56
};
57
65
public
:
Frustum
();
66
79
public
:
Frustum
(
double
_near
,
80
double
_far
,
81
const
math::Angle
&
_fov
,
82
double
_aspectRatio
,
83
const
math::Pose3d
&
_pose
= math::Pose3d::Zero);
84
89
public
:
double
Near
()
const
;
90
95
public
:
void
SetNear
(
double
_near
);
96
101
public
:
double
Far
()
const
;
102
107
public
:
void
SetFar
(
double
_far
);
108
114
public
:
math::Angle
FOV
()
const
;
115
121
public
:
void
SetFOV
(
const
math::Angle
&
_fov
);
122
127
public
:
double
AspectRatio
()
const
;
128
133
public
:
void
SetAspectRatio
(
double
_aspectRatio
);
134
138
public
:
Planed
Plane
(
const
FrustumPlane
_plane
)
const
;
139
143
public
:
bool
Contains
(
const
AxisAlignedBox
&
_b
)
const
;
144
148
public
:
bool
Contains
(
const
Vector3d
&
_p
)
const
;
149
153
public
:
Pose3d
Pose
()
const
;
154
158
public
:
void
SetPose
(
const
Pose3d
&
_pose
);
159
162
private
:
void
ComputePlanes();
163
165
GZ_UTILS_IMPL_PTR
(dataPtr)
166
};
167
}
// GZ_MATH_VERSION_NAMESPACE
168
}
// namespace gz::math
169
#endif
// GZ_MATH_FRUSTUM_HH_