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::HoughLinesConfig | 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 | max_threshold_ |
double | maxLineGap_ |
int | min_threshold_ |
double | minLineLength_ |
ros::Publisher | msg_pub_ |
ros::Time | prev_stamp_ |
int | queue_size_ |
boost::shared_ptr < ReconfigureServer > | reconfigure_server_ |
double | rho_ |
double | theta_ |
int | threshold_ |
std::string | window_name_ |
Static Private Attributes | |
static bool | need_config_update_ = false |
Definition at line 60 of file hough_lines_nodelet.cpp.
typedef opencv_apps::HoughLinesConfig opencv_apps::HoughLinesNodelet::Config [private] |
Definition at line 69 of file hough_lines_nodelet.cpp.
typedef dynamic_reconfigure::Server<Config> opencv_apps::HoughLinesNodelet::ReconfigureServer [private] |
Definition at line 70 of file hough_lines_nodelet.cpp.
void opencv_apps::HoughLinesNodelet::doWork | ( | const sensor_msgs::ImageConstPtr & | msg, |
const std::string & | input_frame_from_msg | ||
) | [inline, private] |
Apply Canny edge detector
Check whether input gray image is filtered such that canny, sobel ...etc
Create Trackbars for Thresholds
1. Use Standard Hough Transform
Show the result
2. Use Probabilistic Hough Transform
Show the result
Definition at line 121 of file hough_lines_nodelet.cpp.
const std::string& opencv_apps::HoughLinesNodelet::frameWithDefault | ( | const std::string & | frame, |
const std::string & | image_frame | ||
) | [inline, private] |
Definition at line 99 of file hough_lines_nodelet.cpp.
void opencv_apps::HoughLinesNodelet::imageCallback | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [inline, private] |
Definition at line 111 of file hough_lines_nodelet.cpp.
void opencv_apps::HoughLinesNodelet::imageCallbackWithInfo | ( | const sensor_msgs::ImageConstPtr & | msg, |
const sensor_msgs::CameraInfoConstPtr & | cam_info | ||
) | [inline, private] |
Definition at line 106 of file hough_lines_nodelet.cpp.
virtual void opencv_apps::HoughLinesNodelet::onInit | ( | ) | [inline, virtual] |
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Reimplemented from opencv_apps::Nodelet.
Reimplemented in hough_lines::HoughLinesNodelet.
Definition at line 287 of file hough_lines_nodelet.cpp.
void opencv_apps::HoughLinesNodelet::reconfigureCallback | ( | Config & | new_config, |
uint32_t | level | ||
) | [inline, private] |
Definition at line 89 of file hough_lines_nodelet.cpp.
void opencv_apps::HoughLinesNodelet::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 270 of file hough_lines_nodelet.cpp.
static void opencv_apps::HoughLinesNodelet::trackbarCallback | ( | int | , |
void * | |||
) | [inline, static, private] |
Definition at line 116 of file hough_lines_nodelet.cpp.
void opencv_apps::HoughLinesNodelet::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 279 of file hough_lines_nodelet.cpp.
Definition at line 64 of file hough_lines_nodelet.cpp.
Definition at line 71 of file hough_lines_nodelet.cpp.
bool opencv_apps::HoughLinesNodelet::debug_view_ [private] |
Definition at line 75 of file hough_lines_nodelet.cpp.
Definition at line 62 of file hough_lines_nodelet.cpp.
Definition at line 63 of file hough_lines_nodelet.cpp.
boost::shared_ptr<image_transport::ImageTransport> opencv_apps::HoughLinesNodelet::it_ [private] |
Definition at line 67 of file hough_lines_nodelet.cpp.
int opencv_apps::HoughLinesNodelet::max_threshold_ [private] |
Definition at line 82 of file hough_lines_nodelet.cpp.
double opencv_apps::HoughLinesNodelet::maxLineGap_ [private] |
Definition at line 87 of file hough_lines_nodelet.cpp.
int opencv_apps::HoughLinesNodelet::min_threshold_ [private] |
Definition at line 81 of file hough_lines_nodelet.cpp.
double opencv_apps::HoughLinesNodelet::minLineLength_ [private] |
Definition at line 86 of file hough_lines_nodelet.cpp.
Definition at line 65 of file hough_lines_nodelet.cpp.
bool opencv_apps::HoughLinesNodelet::need_config_update_ = false [static, private] |
Definition at line 79 of file hough_lines_nodelet.cpp.
Definition at line 76 of file hough_lines_nodelet.cpp.
int opencv_apps::HoughLinesNodelet::queue_size_ [private] |
Definition at line 74 of file hough_lines_nodelet.cpp.
boost::shared_ptr<ReconfigureServer> opencv_apps::HoughLinesNodelet::reconfigure_server_ [private] |
Definition at line 72 of file hough_lines_nodelet.cpp.
double opencv_apps::HoughLinesNodelet::rho_ [private] |
Definition at line 84 of file hough_lines_nodelet.cpp.
double opencv_apps::HoughLinesNodelet::theta_ [private] |
Definition at line 85 of file hough_lines_nodelet.cpp.
int opencv_apps::HoughLinesNodelet::threshold_ [private] |
Definition at line 83 of file hough_lines_nodelet.cpp.
std::string opencv_apps::HoughLinesNodelet::window_name_ [private] |
Definition at line 78 of file hough_lines_nodelet.cpp.