#include <camera_depth_sensor.h>

Public Types | |
| typedef boost::shared_ptr < CameraDepthSensor > | Ptr |
Public Member Functions | |
| CameraDepthSensor () | |
| virtual double | expectedPointCloudNum (double distance, double area) const |
| Return the expected number of points according to distance and area. it is calculated according to: f^2{s}{r^2}. | |
| virtual image_geometry::PinholeCameraModel | getPinholeCameraModel () const |
| get instance of image_geometry::PinholeCameraModel. | |
| virtual int | height () const |
| height of camera in pixels. | |
| virtual cv::Mat | image (const int type) const |
| return an image from internal camera parameter. | |
| virtual bool | isInside (const cv::Point &p) const |
| return true if point p is inside of field-of-view. | |
| virtual cv::Point | limit2DPoint (const cv::Point &p) const |
| force point to be inside of field of view. | |
| virtual void | setCameraInfo (const sensor_msgs::CameraInfo &info) |
| virtual int | width () const |
| width of camera in pixels. | |
Protected Attributes | |
| sensor_msgs::CameraInfo | camera_info_ |
| image_geometry::PinholeCameraModel | model_ |
Definition at line 45 of file camera_depth_sensor.h.
| typedef boost::shared_ptr<CameraDepthSensor> jsk_recognition_utils::CameraDepthSensor::Ptr |
Reimplemented from jsk_recognition_utils::PointCloudSensorModel.
Definition at line 48 of file camera_depth_sensor.h.
Definition at line 49 of file camera_depth_sensor.h.
| virtual double jsk_recognition_utils::CameraDepthSensor::expectedPointCloudNum | ( | double | distance, |
| double | area | ||
| ) | const [inline, virtual] |
Return the expected number of points according to distance and area. it is calculated according to: f^2{s}{r^2}.
Implements jsk_recognition_utils::PointCloudSensorModel.
Definition at line 82 of file camera_depth_sensor.h.
| virtual image_geometry::PinholeCameraModel jsk_recognition_utils::CameraDepthSensor::getPinholeCameraModel | ( | ) | const [inline, virtual] |
get instance of image_geometry::PinholeCameraModel.
Definition at line 61 of file camera_depth_sensor.h.
| virtual int jsk_recognition_utils::CameraDepthSensor::height | ( | ) | const [inline, virtual] |
height of camera in pixels.
Definition at line 110 of file camera_depth_sensor.h.
| virtual cv::Mat jsk_recognition_utils::CameraDepthSensor::image | ( | const int | type | ) | const [inline, virtual] |
return an image from internal camera parameter.
Definition at line 92 of file camera_depth_sensor.h.
| virtual bool jsk_recognition_utils::CameraDepthSensor::isInside | ( | const cv::Point & | p | ) | const [inline, virtual] |
return true if point p is inside of field-of-view.
Definition at line 70 of file camera_depth_sensor.h.
| virtual cv::Point jsk_recognition_utils::CameraDepthSensor::limit2DPoint | ( | const cv::Point & | p | ) | const [inline, virtual] |
force point to be inside of field of view.
Definition at line 119 of file camera_depth_sensor.h.
| virtual void jsk_recognition_utils::CameraDepthSensor::setCameraInfo | ( | const sensor_msgs::CameraInfo & | info | ) | [inline, virtual] |
Definition at line 51 of file camera_depth_sensor.h.
| virtual int jsk_recognition_utils::CameraDepthSensor::width | ( | ) | const [inline, virtual] |
width of camera in pixels.
Definition at line 101 of file camera_depth_sensor.h.
sensor_msgs::CameraInfo jsk_recognition_utils::CameraDepthSensor::camera_info_ [protected] |
Definition at line 127 of file camera_depth_sensor.h.
Definition at line 126 of file camera_depth_sensor.h.