Classes | Public Member Functions | Public Attributes | Static Private Member Functions
CheckerboardDetector Class Reference

List of all members.

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< cv::Point2f > &imgpts, const vector< cv::Point3f > &objpts, const Transform &tlocal, const image_geometry::PinholeCameraModel &model)
void image_cb (const sensor_msgs::ImageConstPtr &msg)
void image_cb2 (const sensor_msgs::ImageConstPtr &msg)
void publishPolygonArray (const posedetection_msgs::ObjectDetection &obj)
void subscribe ()
void unsubscribe ()
virtual ~CheckerboardDetector ()

Public Attributes

sensor_msgs::CameraInfo _camInfoMsg
ros::NodeHandle _node
posedetection_msgs::ObjectDetection _objdetmsg
ros::Publisher _pubCornerPoint
ros::Publisher _pubDetection
ros::Publisher _pubPolygonArray
ros::Publisher _pubPoseStamped
ros::ServiceServer _srvDetect
ros::Subscriber camInfoSubscriber
ros::Subscriber camInfoSubscriber2
int dimx
int dimy
int display
string frame_id
double fRectSize [2]
ros::Subscriber imageSubscriber
ros::Subscriber imageSubscriber2
bool invert_color
ros::Time lasttime
map< string, int > maptypes
int maxboard
int message_throttle_
int message_throttle_counter_
boost::mutex mutexcalib
bool use_P
vector< CHECKERBOARDvcheckers
int verbose
vector< stringvstrtypes

Static Private Member Functions

template<typename T >
static vector< Ttokenizevector (const string &s)

Detailed Description

Definition at line 57 of file checkerboard_detector.cpp.


Constructor & Destructor Documentation

Definition at line 105 of file checkerboard_detector.cpp.

virtual CheckerboardDetector::~CheckerboardDetector ( ) [inline, virtual]

Definition at line 243 of file checkerboard_detector.cpp.


Member Function Documentation

void CheckerboardDetector::caminfo_cb ( const sensor_msgs::CameraInfoConstPtr &  msg) [inline]

Definition at line 249 of file checkerboard_detector.cpp.

void CheckerboardDetector::caminfo_cb2 ( const sensor_msgs::CameraInfoConstPtr &  msg) [inline]

Definition at line 259 of file checkerboard_detector.cpp.

Definition at line 366 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 380 of file checkerboard_detector.cpp.

bool CheckerboardDetector::detect_cb ( posedetection_msgs::Detect::Request &  req,
posedetection_msgs::Detect::Response &  res 
) [inline]

Definition at line 338 of file checkerboard_detector.cpp.

geometry_msgs::Pose CheckerboardDetector::FindTransformation ( const vector< cv::Point2f > &  imgpts,
const vector< cv::Point3f > &  objpts,
const Transform tlocal,
const image_geometry::PinholeCameraModel model 
) [inline]

Definition at line 626 of file checkerboard_detector.cpp.

void CheckerboardDetector::image_cb ( const sensor_msgs::ImageConstPtr &  msg) [inline]

Definition at line 319 of file checkerboard_detector.cpp.

void CheckerboardDetector::image_cb2 ( const sensor_msgs::ImageConstPtr &  msg) [inline]

Definition at line 297 of file checkerboard_detector.cpp.

void CheckerboardDetector::publishPolygonArray ( const posedetection_msgs::ObjectDetection &  obj) [inline]

Definition at line 265 of file checkerboard_detector.cpp.

Definition at line 345 of file checkerboard_detector.cpp.

template<typename T >
static vector<T> CheckerboardDetector::tokenizevector ( const string s) [inline, static, private]

Definition at line 60 of file checkerboard_detector.cpp.

Definition at line 358 of file checkerboard_detector.cpp.


Member Data Documentation

sensor_msgs::CameraInfo CheckerboardDetector::_camInfoMsg

Definition at line 79 of file checkerboard_detector.cpp.

Definition at line 98 of file checkerboard_detector.cpp.

posedetection_msgs::ObjectDetection CheckerboardDetector::_objdetmsg

Definition at line 78 of file checkerboard_detector.cpp.

Definition at line 85 of file checkerboard_detector.cpp.

Definition at line 83 of file checkerboard_detector.cpp.

Definition at line 86 of file checkerboard_detector.cpp.

Definition at line 84 of file checkerboard_detector.cpp.

Definition at line 87 of file checkerboard_detector.cpp.

Definition at line 81 of file checkerboard_detector.cpp.

Definition at line 81 of file checkerboard_detector.cpp.

Definition at line 99 of file checkerboard_detector.cpp.

Definition at line 99 of file checkerboard_detector.cpp.

Definition at line 92 of file checkerboard_detector.cpp.

Definition at line 90 of file checkerboard_detector.cpp.

Definition at line 101 of file checkerboard_detector.cpp.

Definition at line 82 of file checkerboard_detector.cpp.

Definition at line 82 of file checkerboard_detector.cpp.

Definition at line 91 of file checkerboard_detector.cpp.

Definition at line 96 of file checkerboard_detector.cpp.

Definition at line 95 of file checkerboard_detector.cpp.

Definition at line 92 of file checkerboard_detector.cpp.

Definition at line 88 of file checkerboard_detector.cpp.

Definition at line 89 of file checkerboard_detector.cpp.

Definition at line 97 of file checkerboard_detector.cpp.

Definition at line 100 of file checkerboard_detector.cpp.

Definition at line 93 of file checkerboard_detector.cpp.

Definition at line 92 of file checkerboard_detector.cpp.

Definition at line 94 of file checkerboard_detector.cpp.


The documentation for this class was generated from the following file:


checkerboard_detector
Author(s): Rosen Diankov (rdiankov@cs.cmu.edu)
autogenerated on Wed Sep 16 2015 04:37:41