Public Member Functions | |
virtual void | onInit () |
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method. | |
Private Types | |
typedef opencv_apps::ContourMomentsConfig | Config |
typedef dynamic_reconfigure::Server < Config > | ReconfigureServer |
Private Member Functions | |
void | doWork (const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg) |
const std::string & | frameWithDefault (const std::string &frame, const std::string &image_frame) |
void | imageCallback (const sensor_msgs::ImageConstPtr &msg) |
void | imageCallbackWithInfo (const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info) |
void | reconfigureCallback (Config &new_config, uint32_t level) |
void | subscribe () |
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method. | |
void | unsubscribe () |
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this method. | |
Static Private Member Functions | |
static void | trackbarCallback (int, void *) |
Private Attributes | |
image_transport::CameraSubscriber | cam_sub_ |
Config | config_ |
bool | debug_view_ |
image_transport::Publisher | img_pub_ |
image_transport::Subscriber | img_sub_ |
boost::shared_ptr < image_transport::ImageTransport > | it_ |
int | low_threshold_ |
ros::Publisher | msg_pub_ |
ros::Time | prev_stamp_ |
int | queue_size_ |
boost::shared_ptr < ReconfigureServer > | reconfigure_server_ |
std::string | window_name_ |
Static Private Attributes | |
static bool | need_config_update_ = false |
Definition at line 68 of file contour_moments_nodelet.cpp.
typedef opencv_apps::ContourMomentsConfig opencv_apps::ContourMomentsNodelet::Config [private] |
Definition at line 77 of file contour_moments_nodelet.cpp.
typedef dynamic_reconfigure::Server<Config> opencv_apps::ContourMomentsNodelet::ReconfigureServer [private] |
Definition at line 78 of file contour_moments_nodelet.cpp.
void opencv_apps::ContourMomentsNodelet::doWork | ( | const sensor_msgs::ImageConstPtr & | msg, |
const std::string & | input_frame_from_msg | ||
) | [inline, private] |
Convert image to gray and blur it
Create window
Detect edges using canny
Find contours
Draw contours
Calculate the area with the moments 00 and compare with the result of the OpenCV function
Get the moments
Get the mass centers:
Definition at line 119 of file contour_moments_nodelet.cpp.
const std::string& opencv_apps::ContourMomentsNodelet::frameWithDefault | ( | const std::string & | frame, |
const std::string & | image_frame | ||
) | [inline, private] |
Definition at line 97 of file contour_moments_nodelet.cpp.
void opencv_apps::ContourMomentsNodelet::imageCallback | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [inline, private] |
Definition at line 109 of file contour_moments_nodelet.cpp.
void opencv_apps::ContourMomentsNodelet::imageCallbackWithInfo | ( | const sensor_msgs::ImageConstPtr & | msg, |
const sensor_msgs::CameraInfoConstPtr & | cam_info | ||
) | [inline, private] |
Definition at line 104 of file contour_moments_nodelet.cpp.
virtual void opencv_apps::ContourMomentsNodelet::onInit | ( | ) | [inline, virtual] |
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Reimplemented from opencv_apps::Nodelet.
Reimplemented in contour_moments::ContourMomentsNodelet.
Definition at line 269 of file contour_moments_nodelet.cpp.
void opencv_apps::ContourMomentsNodelet::reconfigureCallback | ( | Config & | new_config, |
uint32_t | level | ||
) | [inline, private] |
Definition at line 91 of file contour_moments_nodelet.cpp.
void opencv_apps::ContourMomentsNodelet::subscribe | ( | ) | [inline, private, virtual] |
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
Implements opencv_apps::Nodelet.
Definition at line 252 of file contour_moments_nodelet.cpp.
static void opencv_apps::ContourMomentsNodelet::trackbarCallback | ( | int | , |
void * | |||
) | [inline, static, private] |
Definition at line 114 of file contour_moments_nodelet.cpp.
void opencv_apps::ContourMomentsNodelet::unsubscribe | ( | ) | [inline, private, virtual] |
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this method.
Implements opencv_apps::Nodelet.
Definition at line 261 of file contour_moments_nodelet.cpp.
Definition at line 72 of file contour_moments_nodelet.cpp.
Definition at line 79 of file contour_moments_nodelet.cpp.
bool opencv_apps::ContourMomentsNodelet::debug_view_ [private] |
Definition at line 83 of file contour_moments_nodelet.cpp.
Definition at line 70 of file contour_moments_nodelet.cpp.
Definition at line 71 of file contour_moments_nodelet.cpp.
boost::shared_ptr<image_transport::ImageTransport> opencv_apps::ContourMomentsNodelet::it_ [private] |
Definition at line 75 of file contour_moments_nodelet.cpp.
int opencv_apps::ContourMomentsNodelet::low_threshold_ [private] |
Definition at line 86 of file contour_moments_nodelet.cpp.
Definition at line 73 of file contour_moments_nodelet.cpp.
bool opencv_apps::ContourMomentsNodelet::need_config_update_ = false [static, private] |
Definition at line 89 of file contour_moments_nodelet.cpp.
Definition at line 84 of file contour_moments_nodelet.cpp.
int opencv_apps::ContourMomentsNodelet::queue_size_ [private] |
Definition at line 82 of file contour_moments_nodelet.cpp.
boost::shared_ptr<ReconfigureServer> opencv_apps::ContourMomentsNodelet::reconfigure_server_ [private] |
Definition at line 80 of file contour_moments_nodelet.cpp.
std::string opencv_apps::ContourMomentsNodelet::window_name_ [private] |
Definition at line 88 of file contour_moments_nodelet.cpp.