25 #ifndef TUW_ELLIPSES_H 26 #define TUW_ELLIPSES_H 28 #include "opencv2/core/core.hpp" 31 #include "boost/shared_ptr.hpp" 32 #include <boost/date_time/posix_time/posix_time.hpp> 98 cv::Point3d translations[2];
100 cv::Point2d projections[2];
101 cv::Mat_<double> R[2];
104 for(
unsigned int i = 0; i < 2; i++) {
105 translations[i] = c.translations[i], normals[i] = c.normals[i], projections[i] = c.projections[i];
106 R[i] = c.R[i].clone();
109 void pose(cv::Mat_<double> intrinsic, cv::Mat_<double> distCoeffs,
double radius);
110 void set(cv::RotatedRect box, cv::Mat_<double> intrinsic);
111 double distance(
const cv::Point2d p);
112 void rotation2Normal(
int i);
113 void normal2Roation(
int i);
117 Ellipse(): id(-1), outerRing(-1), innerRing(-1), boxContour(), boxEllipse(), detection(
VALID) {
146 :
ObliqueCone(c), id(-1), tstamp(), A(cv::Mat_<double>::eye(4,4)) {
149 :
ObliqueCone(c), id(c.id), tstamp(c.tstamp), A(c.A.clone()) {
154 void update(
const boost::posix_time::ptime &t);
160 void fit_ellipses_opencv (
const cv::Mat &m,
const cv::Mat cameraMatrix,
const cv::Mat distCoeffs,
const cv::Mat projectionMatrix,
const boost::posix_time::ptime &tstamp);
191 #endif // TUW_ELLIPSES_H
std::list< Marker > markers_
EdgeDetection edge_detection
boost::shared_ptr< std::vector< cv::Point2f > > contourUndistort
boost::posix_time::ptime tstampLast_
cv::Point2d centerContour
void draw_ellipses(cv::Mat &m)
bool update(const T &new_val, T &my_val)
double threshold_ring_ratio
ObliqueCone(const ObliqueCone &c)
PoseEstimation pose_estimation
cv::RotatedRect boxEllipse
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
DetectionState filterContourMean(Ellipse &ellipse)
int threshold_edge_detection1
boost::shared_ptr< std::vector< cv::Point2f > > contourDistort
Marker(const ObliqueCone &c)
std::vector< std::vector< cv::Point > > contours_
tuw::Contour contour_detector_
double threshold_contour_mean
std::vector< Ellipse > ellipses_
int threshold_contour_min_points
DetectionState EllipseRedefinement(Ellipse &ellipse)
boost::posix_time::ptime tstamp_
double threshold_max_radius
double threshold_rotated_rect_ratio
void createEllipseCanditates()
double threshold_ring_center
double threshold_min_radius
boost::shared_ptr< std::vector< cv::Point > > polygon
boost::shared_ptr< std::vector< double > > distances
int kernel_size_edge_detection
bool ellipse_redefinement
boost::posix_time::ptime tstamp
Class to link detected images edges a typical source can be a cvCanny image.
int threshold_edge_detection2
void fit_ellipses_opencv(const cv::Mat &m, const cv::Mat cameraMatrix, const cv::Mat distCoeffs, const cv::Mat projectionMatrix, const boost::posix_time::ptime &tstamp)
cv::Mat_< cv::Point2f > lookupUndistor_
EllipsesDetection(Parameters *parm)
DetectionState filterContour(Ellipse &ellipse)
DetectionState filterEllipse(Ellipse &ellipse)