#include <depth_camera_frustum.hpp>
Definition at line 53 of file depth_camera_frustum.hpp.
geometry::DepthCameraFrustum::DepthCameraFrustum |
( |
const double & |
vFOV, |
|
|
const double & |
hFOV, |
|
|
const double & |
min_dist, |
|
|
const double & |
max_dist |
|
) |
| |
geometry::DepthCameraFrustum::~DepthCameraFrustum |
( |
void |
| ) |
|
|
virtual |
void geometry::DepthCameraFrustum::ComputePlaneNormals |
( |
void |
| ) |
|
|
private |
double geometry::DepthCameraFrustum::Dot |
( |
const VectorWithPt3D & |
plane_pt, |
|
|
const openvdb::Vec3d & |
query_pt |
|
) |
| const |
|
private |
double geometry::DepthCameraFrustum::Dot |
( |
const VectorWithPt3D & |
plane_pt, |
|
|
const Eigen::Vector3d & |
query_pt |
|
) |
| const |
|
private |
bool geometry::DepthCameraFrustum::IsInside |
( |
const openvdb::Vec3d & |
pt | ) |
|
|
virtual |
void geometry::DepthCameraFrustum::SetOrientation |
( |
const geometry_msgs::Quaternion & |
quat | ) |
|
|
virtual |
void geometry::DepthCameraFrustum::TransformModel |
( |
void |
| ) |
|
|
virtual |
double geometry::DepthCameraFrustum::_hFOV |
|
private |
double geometry::DepthCameraFrustum::_max_d |
|
private |
double geometry::DepthCameraFrustum::_min_d |
|
private |
Eigen::Quaterniond geometry::DepthCameraFrustum::_orientation |
|
private |
std::vector<VectorWithPt3D> geometry::DepthCameraFrustum::_plane_normals |
|
private |
Eigen::Vector3d geometry::DepthCameraFrustum::_position |
|
private |
bool geometry::DepthCameraFrustum::_valid_frustum |
|
private |
double geometry::DepthCameraFrustum::_vFOV |
|
private |
The documentation for this class was generated from the following files: