Public Member Functions | |
HoughLines (ros::NodeHandle nh=ros::NodeHandle()) | |
Private Member Functions | |
void | connectCb (const image_transport::SingleSubscriberPublisher &ssp) |
void | disconnectCb (const image_transport::SingleSubscriberPublisher &) |
void | do_work (const sensor_msgs::ImageConstPtr &msg, const std::string input_frame_from_msg) |
void | imageCallback (const sensor_msgs::ImageConstPtr &msg) |
void | reconfigureCallback (jsk_perception::HoughLinesConfig &new_config, uint32_t level) |
void | subscribe () |
void | unsubscribe () |
Private Attributes | |
double | _maxLineGap |
double | _minLineLength |
double | _rho |
double | _theta |
int | _threshold |
jsk_perception::HoughLinesConfig | config_ |
image_transport::Publisher | img_pub_ |
image_transport::Subscriber | img_sub_ |
image_transport::ImageTransport | it_ |
ros::NodeHandle | nh_ |
ros::Publisher | out_pub_ |
dynamic_reconfigure::Server < jsk_perception::HoughLinesConfig > | srv |
int | subscriber_count_ |
Definition at line 15 of file hough_lines.cpp.
HoughLines::HoughLines | ( | ros::NodeHandle | nh = ros::NodeHandle() | ) | [inline] |
Definition at line 146 of file hough_lines.cpp.
void HoughLines::connectCb | ( | const image_transport::SingleSubscriberPublisher & | ssp | ) | [inline, private] |
Definition at line 130 of file hough_lines.cpp.
void HoughLines::disconnectCb | ( | const image_transport::SingleSubscriberPublisher & | ) | [inline, private] |
Definition at line 137 of file hough_lines.cpp.
void HoughLines::do_work | ( | const sensor_msgs::ImageConstPtr & | msg, |
const std::string | input_frame_from_msg | ||
) | [inline, private] |
Definition at line 54 of file hough_lines.cpp.
void HoughLines::imageCallback | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [inline, private] |
Definition at line 49 of file hough_lines.cpp.
void HoughLines::reconfigureCallback | ( | jsk_perception::HoughLinesConfig & | new_config, |
uint32_t | level | ||
) | [inline, private] |
Definition at line 34 of file hough_lines.cpp.
void HoughLines::subscribe | ( | ) | [inline, private] |
Definition at line 118 of file hough_lines.cpp.
void HoughLines::unsubscribe | ( | ) | [inline, private] |
Definition at line 124 of file hough_lines.cpp.
double HoughLines::_maxLineGap [private] |
Definition at line 32 of file hough_lines.cpp.
double HoughLines::_minLineLength [private] |
Definition at line 31 of file hough_lines.cpp.
double HoughLines::_rho [private] |
Definition at line 28 of file hough_lines.cpp.
double HoughLines::_theta [private] |
Definition at line 29 of file hough_lines.cpp.
int HoughLines::_threshold [private] |
Definition at line 30 of file hough_lines.cpp.
jsk_perception::HoughLinesConfig HoughLines::config_ [private] |
Definition at line 17 of file hough_lines.cpp.
Definition at line 20 of file hough_lines.cpp.
Definition at line 21 of file hough_lines.cpp.
Definition at line 24 of file hough_lines.cpp.
ros::NodeHandle HoughLines::nh_ [private] |
Definition at line 25 of file hough_lines.cpp.
ros::Publisher HoughLines::out_pub_ [private] |
Definition at line 22 of file hough_lines.cpp.
dynamic_reconfigure::Server<jsk_perception::HoughLinesConfig> HoughLines::srv [private] |
Definition at line 18 of file hough_lines.cpp.
int HoughLines::subscriber_count_ [private] |
Definition at line 26 of file hough_lines.cpp.