a high level camera wraper including its parameters, and its observer More...
#include <calibration_job.hpp>
Public Member Functions | |
| Camera () | |
| default Constructor | |
| Camera () | |
| default Constructor | |
| Camera (std::string name, CameraParameters camera_parameters, bool is_moving) | |
| Constructor. | |
| Camera (std::string name, CameraParameters camera_parameters, bool is_moving) | |
| Constructor. | |
| bool | isMoving () |
| bool | isMoving () |
| ~Camera () | |
| default destructor, nothing to do really | |
| ~Camera () | |
| default destructor, nothing to do really | |
Public Attributes | |
| std::string | camera_name_ |
| boost::shared_ptr < DummyCameraObserver > | camera_observer_ |
| boost::shared_ptr < ROSCameraObserver > | camera_observer_ |
| CameraParameters | camera_parameters_ |
| bool | fixed_extrinsics_ |
| bool | fixed_intrinsics_ |
Private Attributes | |
| bool | is_moving_ |
a high level camera wraper including its parameters, and its observer
a high level camera wrapper including its parameters, and its observer
Definition at line 33 of file calibration_job.hpp.
| Camera::Camera | ( | ) |
default Constructor
Definition at line 42 of file calibration_job.cpp.
| industrial_extrinsic_cal::Camera::Camera | ( | std::string | name, |
| CameraParameters | camera_parameters, | ||
| bool | is_moving | ||
| ) |
Constructor.
| name | name of camera |
| camera_parameters | intrinsic and extrinsic camera parameters |
| is_moving | static camera = false, moving camera=true |
| Camera::~Camera | ( | ) |
default destructor, nothing to do really
Definition at line 53 of file calibration_job.cpp.
default Constructor
| industrial_extrinsic_cal::Camera::Camera | ( | std::string | name, |
| CameraParameters | camera_parameters, | ||
| bool | is_moving | ||
| ) |
Constructor.
| name | name of camera |
| camera_parameters | intrinsic and extrinsic camera parameters |
| is_moving | static camera = false, moving camera=true |
default destructor, nothing to do really
| bool Camera::isMoving | ( | ) |
is the camera's location fixed or not? moving cameras get multiple pose parameters static cameras get but one set of pose parameters
Definition at line 57 of file calibration_job.cpp.
is the camera's location fixed or not? moving cameras get multiple pose parameters static cameras get but one set of pose parameters
| std::string Camera::camera_name_ |
string camera_name_ unique name of a camera
Definition at line 58 of file calibration_job.hpp.
| boost::shared_ptr<DummyCameraObserver> industrial_extrinsic_cal::Camera::camera_observer_ |
processes images, does CameraObservations
Definition at line 54 of file calibration_job.hpp.
| boost::shared_ptr<ROSCameraObserver> industrial_extrinsic_cal::Camera::camera_observer_ |
processes images, does CameraObservations
Definition at line 55 of file camera_definition.h.
The intrinsic and extrinsic parameters
Definition at line 55 of file calibration_job.hpp.
are the extrinsics known?
Definition at line 61 of file calibration_job.hpp.
Definition at line 60 of file calibration_job.hpp.
bool Camera::is_moving_ [private] |
are the extrinsics known? bool is_moving_ false for static cameras
Definition at line 64 of file calibration_job.hpp.