Classes | |
struct | CHECKERBOARD |
Public Member Functions | |
void | caminfo_cb (const sensor_msgs::CameraInfoConstPtr &msg) |
void | caminfo_cb2 (const sensor_msgs::CameraInfoConstPtr &msg) |
CheckerboardDetector () | |
void | connectCb () |
bool | Detect (posedetection_msgs::ObjectDetection &objdetmsg, const sensor_msgs::Image &imagemsg, const sensor_msgs::CameraInfo &camInfoMsg) |
bool | detect_cb (posedetection_msgs::Detect::Request &req, posedetection_msgs::Detect::Response &res) |
geometry_msgs::Pose | FindTransformation (const vector< CvPoint2D32f > &imgpts, const vector< Vector > &objpts, const Transform &tlocal) |
void | image_cb (const sensor_msgs::ImageConstPtr &msg) |
void | image_cb2 (const sensor_msgs::ImageConstPtr &msg) |
virtual | ~CheckerboardDetector () |
Public Attributes | |
sensor_msgs::CameraInfo | _camInfoMsg |
ros::NodeHandle | _node |
posedetection_msgs::ObjectDetection | _objdetmsg |
ros::Publisher | _pubCornerPoint |
ros::Publisher | _pubDetection |
ros::ServiceServer | _srvDetect |
ros::Subscriber | camInfoSubscriber |
ros::Subscriber | camInfoSubscriber2 |
cv_bridge::CvImagePtr | capture |
int | display |
IplImage * | frame |
string | frame_id |
ros::Subscriber | imageSubscriber |
ros::Subscriber | imageSubscriber2 |
CvMat * | intrinsic_matrix |
ros::Time | lasttime |
map< string, int > | maptypes |
int | maxboard |
boost::mutex | mutexcalib |
vector< CHECKERBOARD > | vcheckers |
int | verbose |
vector< string > | vstrtypes |
Static Private Member Functions | |
template<typename T > | |
static vector< T > | tokenizevector (const string &s) |
Definition at line 50 of file checkerboard_detector.cpp.
CheckerboardDetector::CheckerboardDetector | ( | ) | [inline] |
Definition at line 93 of file checkerboard_detector.cpp.
virtual CheckerboardDetector::~CheckerboardDetector | ( | ) | [inline, virtual] |
Definition at line 203 of file checkerboard_detector.cpp.
void CheckerboardDetector::caminfo_cb | ( | const sensor_msgs::CameraInfoConstPtr & | msg | ) | [inline] |
Definition at line 218 of file checkerboard_detector.cpp.
void CheckerboardDetector::caminfo_cb2 | ( | const sensor_msgs::CameraInfoConstPtr & | msg | ) | [inline] |
Definition at line 228 of file checkerboard_detector.cpp.
void CheckerboardDetector::connectCb | ( | ) | [inline] |
Definition at line 257 of file checkerboard_detector.cpp.
bool CheckerboardDetector::Detect | ( | posedetection_msgs::ObjectDetection & | objdetmsg, |
const sensor_msgs::Image & | imagemsg, | ||
const sensor_msgs::CameraInfo & | camInfoMsg | ||
) | [inline] |
Definition at line 280 of file checkerboard_detector.cpp.
bool CheckerboardDetector::detect_cb | ( | posedetection_msgs::Detect::Request & | req, |
posedetection_msgs::Detect::Response & | res | ||
) | [inline] |
Definition at line 251 of file checkerboard_detector.cpp.
geometry_msgs::Pose CheckerboardDetector::FindTransformation | ( | const vector< CvPoint2D32f > & | imgpts, |
const vector< Vector > & | objpts, | ||
const Transform & | tlocal | ||
) | [inline] |
Definition at line 483 of file checkerboard_detector.cpp.
void CheckerboardDetector::image_cb | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [inline] |
Definition at line 244 of file checkerboard_detector.cpp.
void CheckerboardDetector::image_cb2 | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [inline] |
Definition at line 234 of file checkerboard_detector.cpp.
static vector<T> CheckerboardDetector::tokenizevector | ( | const string & | s | ) | [inline, static, private] |
Definition at line 53 of file checkerboard_detector.cpp.
sensor_msgs::CameraInfo CheckerboardDetector::_camInfoMsg |
Definition at line 70 of file checkerboard_detector.cpp.
Definition at line 89 of file checkerboard_detector.cpp.
posedetection_msgs::ObjectDetection CheckerboardDetector::_objdetmsg |
Definition at line 68 of file checkerboard_detector.cpp.
Definition at line 75 of file checkerboard_detector.cpp.
Definition at line 74 of file checkerboard_detector.cpp.
Definition at line 76 of file checkerboard_detector.cpp.
Definition at line 72 of file checkerboard_detector.cpp.
Definition at line 72 of file checkerboard_detector.cpp.
Definition at line 69 of file checkerboard_detector.cpp.
Definition at line 80 of file checkerboard_detector.cpp.
IplImage* CheckerboardDetector::frame |
Definition at line 87 of file checkerboard_detector.cpp.
Definition at line 78 of file checkerboard_detector.cpp.
Definition at line 73 of file checkerboard_detector.cpp.
Definition at line 73 of file checkerboard_detector.cpp.
Definition at line 85 of file checkerboard_detector.cpp.
Definition at line 84 of file checkerboard_detector.cpp.
map<string,int> CheckerboardDetector::maptypes |
Definition at line 83 of file checkerboard_detector.cpp.
Definition at line 80 of file checkerboard_detector.cpp.
boost::mutex CheckerboardDetector::mutexcalib |
Definition at line 86 of file checkerboard_detector.cpp.
Definition at line 81 of file checkerboard_detector.cpp.
Definition at line 80 of file checkerboard_detector.cpp.
Definition at line 82 of file checkerboard_detector.cpp.