#include <camera_depth_sensor.h>
Public Types | |
typedef boost::shared_ptr< CameraDepthSensor > | Ptr |
Public Types inherited from jsk_recognition_utils::PointCloudSensorModel | |
typedef boost::shared_ptr< PointCloudSensorModel > | 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\frac{s}{r^2}. More... | |
virtual image_geometry::PinholeCameraModel | getPinholeCameraModel () const |
get instance of image_geometry::PinholeCameraModel. More... | |
virtual int | height () const |
height of camera in pixels. More... | |
virtual cv::Mat | image (const int type) const |
return an image from internal camera parameter. More... | |
virtual bool | isInside (const cv::Point &p) const |
return true if point p is inside of field-of-view. More... | |
virtual cv::Point | limit2DPoint (const cv::Point &p) const |
force point to be inside of field of view. More... | |
virtual void | setCameraInfo (const sensor_msgs::CameraInfo &info) |
virtual int | width () const |
width of camera in pixels. More... | |
Protected Attributes | |
sensor_msgs::CameraInfo | camera_info_ |
image_geometry::PinholeCameraModel | model_ |
Definition at line 77 of file camera_depth_sensor.h.
Definition at line 112 of file camera_depth_sensor.h.
|
inline |
Definition at line 113 of file camera_depth_sensor.h.
|
inlinevirtual |
Return the expected number of points according to distance and area. it is calculated according to: f^2\frac{s}{r^2}.
Implements jsk_recognition_utils::PointCloudSensorModel.
Definition at line 146 of file camera_depth_sensor.h.
|
inlinevirtual |
get instance of image_geometry::PinholeCameraModel.
Definition at line 125 of file camera_depth_sensor.h.
|
inlinevirtual |
height of camera in pixels.
Definition at line 174 of file camera_depth_sensor.h.
|
inlinevirtual |
return an image from internal camera parameter.
Definition at line 156 of file camera_depth_sensor.h.
|
inlinevirtual |
return true if point p is inside of field-of-view.
Definition at line 134 of file camera_depth_sensor.h.
|
inlinevirtual |
force point to be inside of field of view.
Definition at line 183 of file camera_depth_sensor.h.
|
inlinevirtual |
Definition at line 115 of file camera_depth_sensor.h.
|
inlinevirtual |
width of camera in pixels.
Definition at line 165 of file camera_depth_sensor.h.
|
protected |
Definition at line 191 of file camera_depth_sensor.h.
|
protected |
Definition at line 190 of file camera_depth_sensor.h.