#include <TextLocator.hpp>
Public Member Functions | |
TDetector & | getDetector () |
TRecognizer & | getRecognizer () |
bool | isPclEnabled () const |
bool | isRecognitionEnabled () const |
void | run () |
TextLocator () | |
TextLocator (ros::NodeHandle &handle, tesseract::PageSegMode pgSegMode, std::string lang, std::vector< ccv_swt_param_t > params, const bool enableRecognition, const bool paramDebug, const bool enablePcl) | |
Private Member Functions | |
void | depthCallback (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &depth) |
void | init () |
void | monoCallback (const sensor_msgs::ImageConstPtr &image) |
void | publish (pcl::PointXYZRGB &p1, pcl::PointXYZRGB &p2, std::string txt) |
int | rgbToIrX (int rgb) |
int | rgbToIrY (int rgb) |
void | saveDbgImg (const sensor_msgs::ImageConstPtr &image) |
Private Attributes | |
cv_bridge::CvImageConstPtr | cv_ptr |
TDetector | detector |
volatile bool | newdata |
ros::NodeHandle & | nodehandler |
const bool | paramDebugMode |
const bool | pclEnabled |
ros::Publisher | pub |
TRecognizer | rec |
const bool | recognitionEnabled |
float | rgb2IrX |
float | rgb2IrY |
ros::Subscriber | sub |
ros::Subscriber | sub2 |
std::vector< Text2D > | text2d |
Definition at line 43 of file TextLocator.hpp.
ros_text_locator::TextLocator::TextLocator | ( | ros::NodeHandle & | handle, |
tesseract::PageSegMode | pgSegMode, | ||
std::string | lang, | ||
std::vector< ccv_swt_param_t > | params, | ||
const bool | enableRecognition, | ||
const bool | paramDebug, | ||
const bool | enablePcl | ||
) |
Definition at line 50 of file TextLocator.cpp.
void ros_text_locator::TextLocator::depthCallback | ( | const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr & | depth | ) | [private] |
Definition at line 137 of file TextLocator.cpp.
TDetector& ros_text_locator::TextLocator::getDetector | ( | ) | [inline] |
Definition at line 86 of file TextLocator.hpp.
TRecognizer& ros_text_locator::TextLocator::getRecognizer | ( | ) | [inline] |
Definition at line 90 of file TextLocator.hpp.
void ros_text_locator::TextLocator::init | ( | ) | [private] |
Definition at line 68 of file TextLocator.cpp.
bool ros_text_locator::TextLocator::isPclEnabled | ( | ) | const [inline] |
Definition at line 82 of file TextLocator.hpp.
bool ros_text_locator::TextLocator::isRecognitionEnabled | ( | ) | const [inline] |
Definition at line 78 of file TextLocator.hpp.
void ros_text_locator::TextLocator::monoCallback | ( | const sensor_msgs::ImageConstPtr & | image | ) | [private] |
Definition at line 113 of file TextLocator.cpp.
void ros_text_locator::TextLocator::publish | ( | pcl::PointXYZRGB & | p1, |
pcl::PointXYZRGB & | p2, | ||
std::string | txt | ||
) | [private] |
Definition at line 173 of file TextLocator.cpp.
int ros_text_locator::TextLocator::rgbToIrX | ( | int | rgb | ) | [private] |
Definition at line 165 of file TextLocator.cpp.
int ros_text_locator::TextLocator::rgbToIrY | ( | int | rgb | ) | [private] |
Definition at line 169 of file TextLocator.cpp.
void ros_text_locator::TextLocator::run | ( | ) |
Definition at line 91 of file TextLocator.cpp.
void ros_text_locator::TextLocator::saveDbgImg | ( | const sensor_msgs::ImageConstPtr & | image | ) | [private] |
Definition at line 194 of file TextLocator.cpp.
Definition at line 59 of file TextLocator.hpp.
Definition at line 46 of file TextLocator.hpp.
volatile bool ros_text_locator::TextLocator::newdata [private] |
Definition at line 49 of file TextLocator.hpp.
Definition at line 50 of file TextLocator.hpp.
const bool ros_text_locator::TextLocator::paramDebugMode [private] |
Definition at line 47 of file TextLocator.hpp.
const bool ros_text_locator::TextLocator::pclEnabled [private] |
Definition at line 51 of file TextLocator.hpp.
Definition at line 56 of file TextLocator.hpp.
Definition at line 45 of file TextLocator.hpp.
const bool ros_text_locator::TextLocator::recognitionEnabled [private] |
Definition at line 48 of file TextLocator.hpp.
float ros_text_locator::TextLocator::rgb2IrX [private] |
Definition at line 53 of file TextLocator.hpp.
float ros_text_locator::TextLocator::rgb2IrY [private] |
Definition at line 54 of file TextLocator.hpp.
Definition at line 57 of file TextLocator.hpp.
Definition at line 58 of file TextLocator.hpp.
std::vector<Text2D> ros_text_locator::TextLocator::text2d [private] |
Definition at line 55 of file TextLocator.hpp.