#include <SRCalibratedLib.h>
Public Member Functions | |
void | calc3DPoints (sensor_msgs::PointCloud &pts_) |
int | height () |
void | setRengeImg (const sensor_msgs::ImageConstPtr &img_conf, const sensor_msgs::ImageConstPtr &img_intent, const sensor_msgs::ImageConstPtr &img_depth, const sensor_msgs::CameraInfoConstPtr &info) |
SRCalibratedLib () | |
int | width () |
Public Attributes | |
int | confidence_threshold |
double | depth_scale |
int | dilate_times |
double | edge1 |
double | edge2 |
int | intensity_threshold |
double | max_range |
bool | short_range |
double | smooth_depth |
int | smooth_size |
double | smooth_space |
bool | use_filter |
bool | use_smooth |
Protected Member Functions | |
void | convert3DPos (sensor_msgs::PointCloud &pts) |
void | makeConvertMap () |
Private Attributes | |
CvMat * | cam_matrix |
CvMat * | dist_coeff |
sensor_msgs::CameraInfo | info_depth_ |
IplImage * | ipl_depth_ |
float * | map_x |
float * | map_y |
float * | map_z |
int | srheight |
int | srwidth |
Definition at line 10 of file SRCalibratedLib.h.
Definition at line 108 of file SRCalibratedLib.cpp.
void SRCalibratedLib::calc3DPoints | ( | sensor_msgs::PointCloud & | pts_ | ) |
Definition at line 161 of file SRCalibratedLib.cpp.
void SRCalibratedLib::convert3DPos | ( | sensor_msgs::PointCloud & | pts | ) | [protected] |
Definition at line 75 of file SRCalibratedLib.cpp.
int SRCalibratedLib::height | ( | ) | [inline] |
Definition at line 49 of file SRCalibratedLib.h.
void SRCalibratedLib::makeConvertMap | ( | ) | [protected] |
Definition at line 4 of file SRCalibratedLib.cpp.
void SRCalibratedLib::setRengeImg | ( | const sensor_msgs::ImageConstPtr & | img_conf, |
const sensor_msgs::ImageConstPtr & | img_intent, | ||
const sensor_msgs::ImageConstPtr & | img_depth, | ||
const sensor_msgs::CameraInfoConstPtr & | info | ||
) |
Definition at line 119 of file SRCalibratedLib.cpp.
int SRCalibratedLib::width | ( | ) | [inline] |
Definition at line 43 of file SRCalibratedLib.h.
CvMat* SRCalibratedLib::cam_matrix [private] |
Definition at line 16 of file SRCalibratedLib.h.
Definition at line 30 of file SRCalibratedLib.h.
double SRCalibratedLib::depth_scale |
Definition at line 28 of file SRCalibratedLib.h.
Definition at line 38 of file SRCalibratedLib.h.
CvMat * SRCalibratedLib::dist_coeff [private] |
Definition at line 16 of file SRCalibratedLib.h.
double SRCalibratedLib::edge1 |
Definition at line 37 of file SRCalibratedLib.h.
double SRCalibratedLib::edge2 |
Definition at line 37 of file SRCalibratedLib.h.
sensor_msgs::CameraInfo SRCalibratedLib::info_depth_ [private] |
Definition at line 12 of file SRCalibratedLib.h.
Definition at line 30 of file SRCalibratedLib.h.
IplImage* SRCalibratedLib::ipl_depth_ [private] |
Definition at line 13 of file SRCalibratedLib.h.
float* SRCalibratedLib::map_x [private] |
Definition at line 14 of file SRCalibratedLib.h.
float * SRCalibratedLib::map_y [private] |
Definition at line 14 of file SRCalibratedLib.h.
float * SRCalibratedLib::map_z [private] |
Definition at line 14 of file SRCalibratedLib.h.
double SRCalibratedLib::max_range |
Definition at line 27 of file SRCalibratedLib.h.
Definition at line 29 of file SRCalibratedLib.h.
Definition at line 34 of file SRCalibratedLib.h.
Definition at line 33 of file SRCalibratedLib.h.
Definition at line 34 of file SRCalibratedLib.h.
int SRCalibratedLib::srheight [private] |
Definition at line 15 of file SRCalibratedLib.h.
int SRCalibratedLib::srwidth [private] |
Definition at line 15 of file SRCalibratedLib.h.
Definition at line 36 of file SRCalibratedLib.h.
Definition at line 32 of file SRCalibratedLib.h.