Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
tuw::EllipsesDetectionNode Class Reference

ROS Node. More...

#include <ellipses_nodelet.h>

Inheritance diagram for tuw::EllipsesDetectionNode:
Inheritance graph
[legend]

Classes

struct  ParametersNode
 

Public Member Functions

 EllipsesDetectionNode ()
 
void imageCallback (const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
 
void init ()
 
virtual void onInit ()
 
 ~EllipsesDetectionNode ()
 
- Public Member Functions inherited from tuw::EllipsesDetection
 EllipsesDetection (Parameters *parm)
 
 ~EllipsesDetection ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Private Member Functions

void createTransforms (const std_msgs::Header &header)
 
const ParametersNodeparam ()
 
void publishFiducials (const std_msgs::Header &header)
 
void publishMarker (const std_msgs::Header &header)
 
void publishTf ()
 
void update ()
 

Private Attributes

unsigned long callback_counter_
 
sensor_msgs::CameraInfoConstPtr camera_info_
 
cv_bridge::CvImagePtr image_mono_
 
image_transport::ImageTransport imageTransport_
 
std::list< tf::StampedTransformmarkerTransforms_
 
ros::NodeHandle n_
 
ros::Publisher pub_ellipses_
 
ros::Publisher pub_fiducials_
 
ros::Publisher pub_perceptions_
 
image_transport::CameraSubscriber sub_camera_
 
boost::posix_time::ptime timeCallbackReceived_
 
boost::posix_time::ptime timeCallbackReceivedLast_
 
boost::posix_time::ptime timeDetectionEnd_
 
boost::posix_time::ptime timeDetectionStart_
 
tf::TransformBroadcaster transformBroadcaster_
 

Additional Inherited Members

- Public Types inherited from tuw::EllipsesDetection
enum  DetectionState {
  VALID = 0, NA = 1, INVALID_CONTOUR_POINTS, INVALID_CONTOUR_CONVEX,
  INVALID_ROTATED_RECT_RATIO, INVALID_CONTOUR_MEAN, INVALID_MIN_RAIDUS, INVALID_MAX_RAIDUS,
  INVALID_NO_RING, INVALID_IS_INNER_RING, INVALID_ELLIPSE
}
 
enum  EdgeDetection { EDGE_DETECTION_THRESHOLD = 0, EDGE_DETECTION_CANNY = 1 }
 
enum  EdgeLinking {
  EDGE_LINKING_OPENCV_APPROX_NONE = 0, EDGE_LINKING_OPENCV_APPROX_SIMPLE = 1, EDGE_LINKING_TUW_SIMPLE = 2, EDGE_LINKING_TUW_COMPLEX = 3,
  EDGE_LINKING_TUW_CONTOUR = 4
}
 
enum  PoseEstimation { POSE_ESTIMATION_OFF = 0, POSE_ESTIMATION_SOLVEPNP = 1, POSE_ESTIMATION_FROM_ELLIPSE = 2 }
 
- Protected Member Functions inherited from tuw::EllipsesDetection
void contour_detection ()
 
void createEllipseCanditates ()
 
void createRings ()
 
void draw_ellipses (cv::Mat &m)
 
void edge_detection (const cv::Mat &m)
 
DetectionState EllipseRedefinement (Ellipse &ellipse)
 
void estimatePoses ()
 
DetectionState filterContour (Ellipse &ellipse)
 
DetectionState filterContourMean (Ellipse &ellipse)
 
DetectionState filterEllipse (Ellipse &ellipse)
 
void filterShapes ()
 
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)
 
void next ()
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 
- Protected Attributes inherited from tuw::EllipsesDetection
tuw::Camera camera_
 
tuw::Contour contour_detector_
 
std::vector< std::vector< cv::Point > > contours_
 
std::vector< Ellipseellipses_
 
cv::Mat imgBlured_
 
cv::Mat imgDirection_
 
cv::Mat imgEdges_
 
cv::Mat imgGradient_
 
cv::Mat imgGray_
 
cv::Mat imgSobelDx_
 
cv::Mat imgSobelDy_
 
cv::Mat_< cv::Point2f > lookupUndistor_
 
unsigned long loop_count
 
std::list< Markermarkers_
 
Parametersparam_
 
boost::posix_time::ptime tstamp_
 
boost::posix_time::ptime tstampLast_
 

Detailed Description

ROS Node.

Definition at line 50 of file ellipses_nodelet.h.

Constructor & Destructor Documentation

EllipsesDetectionNode::EllipsesDetectionNode ( )

Definition at line 45 of file ellipses_nodelet.cpp.

EllipsesDetectionNode::~EllipsesDetectionNode ( )

Definition at line 42 of file ellipses_nodelet.cpp.

Member Function Documentation

void EllipsesDetectionNode::createTransforms ( const std_msgs::Header header)
private

Definition at line 132 of file ellipses_nodelet.cpp.

void EllipsesDetectionNode::imageCallback ( const sensor_msgs::ImageConstPtr &  image_msg,
const sensor_msgs::CameraInfoConstPtr &  info_msg 
)

Definition at line 60 of file ellipses_nodelet.cpp.

void EllipsesDetectionNode::init ( )

Definition at line 54 of file ellipses_nodelet.cpp.

void EllipsesDetectionNode::onInit ( )
virtual

Implements nodelet::Nodelet.

Definition at line 127 of file ellipses_nodelet.cpp.

const EllipsesDetectionNode::ParametersNode * EllipsesDetectionNode::param ( )
private

Definition at line 50 of file ellipses_nodelet.cpp.

void EllipsesDetectionNode::publishFiducials ( const std_msgs::Header header)
private

Definition at line 202 of file ellipses_nodelet.cpp.

void EllipsesDetectionNode::publishMarker ( const std_msgs::Header header)
private

Definition at line 166 of file ellipses_nodelet.cpp.

void EllipsesDetectionNode::publishTf ( )
private

Definition at line 159 of file ellipses_nodelet.cpp.

void tuw::EllipsesDetectionNode::update ( )
private

Member Data Documentation

unsigned long tuw::EllipsesDetectionNode::callback_counter_
private

Definition at line 85 of file ellipses_nodelet.h.

sensor_msgs::CameraInfoConstPtr tuw::EllipsesDetectionNode::camera_info_
private

Definition at line 93 of file ellipses_nodelet.h.

cv_bridge::CvImagePtr tuw::EllipsesDetectionNode::image_mono_
private

Definition at line 92 of file ellipses_nodelet.h.

image_transport::ImageTransport tuw::EllipsesDetectionNode::imageTransport_
private

Definition at line 90 of file ellipses_nodelet.h.

std::list<tf::StampedTransform> tuw::EllipsesDetectionNode::markerTransforms_
private

Definition at line 98 of file ellipses_nodelet.h.

ros::NodeHandle tuw::EllipsesDetectionNode::n_
private

Definition at line 84 of file ellipses_nodelet.h.

ros::Publisher tuw::EllipsesDetectionNode::pub_ellipses_
private

Definition at line 87 of file ellipses_nodelet.h.

ros::Publisher tuw::EllipsesDetectionNode::pub_fiducials_
private

Definition at line 89 of file ellipses_nodelet.h.

ros::Publisher tuw::EllipsesDetectionNode::pub_perceptions_
private

Definition at line 88 of file ellipses_nodelet.h.

image_transport::CameraSubscriber tuw::EllipsesDetectionNode::sub_camera_
private

Definition at line 91 of file ellipses_nodelet.h.

boost::posix_time::ptime tuw::EllipsesDetectionNode::timeCallbackReceived_
private

Definition at line 95 of file ellipses_nodelet.h.

boost::posix_time::ptime tuw::EllipsesDetectionNode::timeCallbackReceivedLast_
private

Definition at line 94 of file ellipses_nodelet.h.

boost::posix_time::ptime tuw::EllipsesDetectionNode::timeDetectionEnd_
private

Definition at line 97 of file ellipses_nodelet.h.

boost::posix_time::ptime tuw::EllipsesDetectionNode::timeDetectionStart_
private

Definition at line 96 of file ellipses_nodelet.h.

tf::TransformBroadcaster tuw::EllipsesDetectionNode::transformBroadcaster_
private

Definition at line 86 of file ellipses_nodelet.h.


The documentation for this class was generated from the following files:


tuw_ellipses
Author(s): Markus Bader
autogenerated on Mon Jun 10 2019 15:42:10