#include <field_of_view.h>
Public Member Functions | |
| void | computeFieldOfView () |
| calculates coordinate system from parameters | |
| FieldOfView () | |
| void | getFOV (Eigen::Vector3d &p_0, Eigen::Vector3d &p_1, Eigen::Vector3d &p_2, Eigen::Vector3d &p_3, Eigen::Vector3d &p_4) |
| Return the FOV. | |
| void | setSensorFoV_hor (double val) |
| Set the horizontal FOV angle of the camera (degree). | |
| void | setSensorFoV_ver (double val) |
| Set the vertical FOV angle of the camera (degree). | |
| void | setSensorMaxRange (double val) |
| Set the maximum range of the camera (meter). | |
| void | transformFOV (Eigen::Affine3d &t) |
| uses global transformation (of the robot) to recalculate the field of view | |
| ~FieldOfView () | |
Protected Attributes | |
| Eigen::Vector3d | p_0_ |
| maximum range of sensor | |
| Eigen::Vector3d | p_0_cam_ |
| part of view frustum | |
| Eigen::Vector3d | p_1_ |
| part of view frustum | |
| Eigen::Vector3d | p_1_cam_ |
| part of view frustum | |
| Eigen::Vector3d | p_2_ |
| part of view frustum | |
| Eigen::Vector3d | p_2_cam_ |
| part of view frustum | |
| Eigen::Vector3d | p_3_ |
| part of view frustum | |
| Eigen::Vector3d | p_3_cam_ |
| part of view frustum | |
| Eigen::Vector3d | p_4_ |
| part of view frustum | |
| Eigen::Vector3d | p_4_cam_ |
| part of view frustum | |
| double | sensor_fov_hor_ |
| double | sensor_fov_ver_ |
| horizontal angle of sensor | |
| double | sensor_max_range_ |
| vertical angle of sensor | |
Definition at line 76 of file field_of_view.h.
| cob_3d_mapping::FieldOfView::FieldOfView | ( | ) | [inline] |
Constructor
Definition at line 80 of file field_of_view.h.
| cob_3d_mapping::FieldOfView::~FieldOfView | ( | ) | [inline] |
| void FieldOfView::computeFieldOfView | ( | ) |
calculates coordinate system from parameters
calculates coordinate system from parameters
Definition at line 67 of file field_of_view.cpp.
| void cob_3d_mapping::FieldOfView::getFOV | ( | Eigen::Vector3d & | p_0, |
| Eigen::Vector3d & | p_1, | ||
| Eigen::Vector3d & | p_2, | ||
| Eigen::Vector3d & | p_3, | ||
| Eigen::Vector3d & | p_4 | ||
| ) | [inline] |
Return the FOV.
| [out] | p_0 | Origin point. |
| [out] | p_1 | First corner point of the frustum far plane. |
| [out] | p_2 | Second corner point of the frustum far plane. |
| [out] | p_3 | Third corner point of the frustum far plane. |
| [out] | p_4 | Forth corner point of the frustum far plane. |
Definition at line 136 of file field_of_view.h.
| void cob_3d_mapping::FieldOfView::setSensorFoV_hor | ( | double | val | ) | [inline] |
Set the horizontal FOV angle of the camera (degree).
| [in] | val | The angle in degree. |
Definition at line 98 of file field_of_view.h.
| void cob_3d_mapping::FieldOfView::setSensorFoV_ver | ( | double | val | ) | [inline] |
Set the vertical FOV angle of the camera (degree).
| [in] | val | The angle in degree. |
Definition at line 109 of file field_of_view.h.
| void cob_3d_mapping::FieldOfView::setSensorMaxRange | ( | double | val | ) | [inline] |
Set the maximum range of the camera (meter).
| [in] | val | The maximum range in meter. |
Definition at line 120 of file field_of_view.h.
| void cob_3d_mapping::FieldOfView::transformFOV | ( | Eigen::Affine3d & | t | ) | [inline] |
uses global transformation (of the robot) to recalculate the field of view
uses global transformation (of the robot) to recalculate the field of view (all vectors)
| stamp | timestamp indicating used frame |
| target_frame | targetframe |
Definition at line 167 of file field_of_view.h.
Eigen::Vector3d cob_3d_mapping::FieldOfView::p_0_ [protected] |
maximum range of sensor
Definition at line 181 of file field_of_view.h.
Eigen::Vector3d cob_3d_mapping::FieldOfView::p_0_cam_ [protected] |
part of view frustum
Definition at line 187 of file field_of_view.h.
Eigen::Vector3d cob_3d_mapping::FieldOfView::p_1_ [protected] |
part of view frustum
Definition at line 182 of file field_of_view.h.
Eigen::Vector3d cob_3d_mapping::FieldOfView::p_1_cam_ [protected] |
part of view frustum
Definition at line 188 of file field_of_view.h.
Eigen::Vector3d cob_3d_mapping::FieldOfView::p_2_ [protected] |
part of view frustum
Definition at line 183 of file field_of_view.h.
Eigen::Vector3d cob_3d_mapping::FieldOfView::p_2_cam_ [protected] |
part of view frustum
Definition at line 189 of file field_of_view.h.
Eigen::Vector3d cob_3d_mapping::FieldOfView::p_3_ [protected] |
part of view frustum
Definition at line 184 of file field_of_view.h.
Eigen::Vector3d cob_3d_mapping::FieldOfView::p_3_cam_ [protected] |
part of view frustum
Definition at line 190 of file field_of_view.h.
Eigen::Vector3d cob_3d_mapping::FieldOfView::p_4_ [protected] |
part of view frustum
Definition at line 185 of file field_of_view.h.
Eigen::Vector3d cob_3d_mapping::FieldOfView::p_4_cam_ [protected] |
part of view frustum
Definition at line 191 of file field_of_view.h.
double cob_3d_mapping::FieldOfView::sensor_fov_hor_ [protected] |
Definition at line 177 of file field_of_view.h.
double cob_3d_mapping::FieldOfView::sensor_fov_ver_ [protected] |
horizontal angle of sensor
Definition at line 178 of file field_of_view.h.
double cob_3d_mapping::FieldOfView::sensor_max_range_ [protected] |
vertical angle of sensor
Definition at line 179 of file field_of_view.h.