#include <cv_detection.h>
Public Member Functions | |
DetectionCV (ros::NodeHandle &nh_) | |
~DetectionCV (void) | |
Protected Attributes | |
int | p_initial_r |
int | p_initial_x |
int | p_initial_y |
Private Member Functions | |
double | binaryfit_C1 (IplImage *Img, IplImage *H_phi, int nrow, int ncol) |
double | binaryfit_C2 (IplImage *Img, IplImage *H_phi, int nrow, int ncol) |
void | CV_Detect (IplImage *UNImg, CvPoint &Plane) |
void | Delta (IplImage *phi, double epsilon, IplImage *Delta_h) |
void | EVOL_CV (IplImage *I, IplImage *phi, double nu, double lambda_1, double lambda_2, double timestep, double epsilon, int numIter) |
void | Heaviside (IplImage *phi, double epsilon, IplImage *H) |
void | ImageConvert (IplImage *srcImg, int nrow, int ncol) |
void | ImageProcess_1 (IplImage *phi, int nrow, int ncol) |
void | NeumannBoundCond (IplImage *phi) |
void | object_detection (const sensor_msgs::ImageConstPtr &msg) |
void | PlanePoint (IplImage *ProcessImg_1, IplImage *SImg, int nrow, int ncol, CvPoint &PlanePoint) |
void | sdf2circle (IplImage *Phi_0, int nrow, int ncol, int Next_X, int Next_Y, int r, CvSize ImgSize) |
void | ShowIndex (int row, int col, IplImage *srcImg) |
double | Sum (IplImage *srcImg, int nrow, int ncol) |
Private Attributes | |
image_transport::Subscriber | camera_sub_ |
ros::Publisher | image_object_pub_ |
image_transport::ImageTransport | it_ |
CvPoint | object |
ros::Subscriber | object_pridict_sub_ |
Definition at line 54 of file cv_detection.h.
DetectionCV::DetectionCV | ( | ros::NodeHandle & | nh_ | ) |
Definition at line 59 of file cv_detection.cpp.
DetectionCV::~DetectionCV | ( | void | ) |
Definition at line 76 of file cv_detection.cpp.
double DetectionCV::binaryfit_C1 | ( | IplImage * | Img, |
IplImage * | H_phi, | ||
int | nrow, | ||
int | ncol | ||
) | [private] |
Definition at line 229 of file cv_detection.cpp.
double DetectionCV::binaryfit_C2 | ( | IplImage * | Img, |
IplImage * | H_phi, | ||
int | nrow, | ||
int | ncol | ||
) | [private] |
Definition at line 244 of file cv_detection.cpp.
void DetectionCV::CV_Detect | ( | IplImage * | UNImg, |
CvPoint & | Plane | ||
) | [private] |
Definition at line 364 of file cv_detection.cpp.
void DetectionCV::Delta | ( | IplImage * | phi, |
double | epsilon, | ||
IplImage * | Delta_h | ||
) | [private] |
Definition at line 189 of file cv_detection.cpp.
void DetectionCV::EVOL_CV | ( | IplImage * | I, |
IplImage * | phi, | ||
double | nu, | ||
double | lambda_1, | ||
double | lambda_2, | ||
double | timestep, | ||
double | epsilon, | ||
int | numIter | ||
) | [private] |
Definition at line 258 of file cv_detection.cpp.
void DetectionCV::Heaviside | ( | IplImage * | phi, |
double | epsilon, | ||
IplImage * | H | ||
) | [private] |
Definition at line 175 of file cv_detection.cpp.
void DetectionCV::ImageConvert | ( | IplImage * | srcImg, |
int | nrow, | ||
int | ncol | ||
) | [private] |
Definition at line 137 of file cv_detection.cpp.
void DetectionCV::ImageProcess_1 | ( | IplImage * | phi, |
int | nrow, | ||
int | ncol | ||
) | [private] |
Definition at line 314 of file cv_detection.cpp.
void DetectionCV::NeumannBoundCond | ( | IplImage * | phi | ) | [private] |
Definition at line 201 of file cv_detection.cpp.
void DetectionCV::object_detection | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [private] |
Definition at line 81 of file cv_detection.cpp.
void DetectionCV::PlanePoint | ( | IplImage * | ProcessImg_1, |
IplImage * | SImg, | ||
int | nrow, | ||
int | ncol, | ||
CvPoint & | PlanePoint | ||
) | [private] |
Definition at line 333 of file cv_detection.cpp.
void DetectionCV::sdf2circle | ( | IplImage * | Phi_0, |
int | nrow, | ||
int | ncol, | ||
int | Next_X, | ||
int | Next_Y, | ||
int | r, | ||
CvSize | ImgSize | ||
) | [private] |
Definition at line 164 of file cv_detection.cpp.
void DetectionCV::ShowIndex | ( | int | row, |
int | col, | ||
IplImage * | srcImg | ||
) | [private] |
Definition at line 124 of file cv_detection.cpp.
double DetectionCV::Sum | ( | IplImage * | srcImg, |
int | nrow, | ||
int | ncol | ||
) | [private] |
Definition at line 110 of file cv_detection.cpp.
Definition at line 59 of file cv_detection.h.
ros::Publisher DetectionCV::image_object_pub_ [private] |
Definition at line 56 of file cv_detection.h.
Definition at line 58 of file cv_detection.h.
CvPoint DetectionCV::object [private] |
Definition at line 63 of file cv_detection.h.
Definition at line 61 of file cv_detection.h.
int DetectionCV::p_initial_r [protected] |
Definition at line 72 of file cv_detection.h.
int DetectionCV::p_initial_x [protected] |
Definition at line 70 of file cv_detection.h.
int DetectionCV::p_initial_y [protected] |
Definition at line 71 of file cv_detection.h.