Classes | |
| struct | CHECKERBOARD |
Public Member Functions | |
| void | activate (bool active, string image_topic=std::string(), string camera_info_topic=std::string()) |
| void | caminfo_cb (const sensor_msgs::CameraInfoConstPtr &msg) |
| void | caminfo_cb (const sensor_msgs::CameraInfoConstPtr &msg) |
| void | caminfo_cb2 (const sensor_msgs::CameraInfoConstPtr &msg) |
| CheckerboardDetector () | |
| CheckerboardDetector () | |
| bool | Detect (posedetection_msgs::ObjectDetection &objdetmsg, const sensor_msgs::Image &imagemsg, const sensor_msgs::CameraInfo &camInfoMsg) |
| bool | Detect (checkerboard_detector2::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) |
| bool | detect_cb (checkerboard_detector2::Detect::Request &req, checkerboard_detector2::Detect::Response &res) |
| geometry_msgs::Pose | FindTransformation (const vector< CvPoint2D32f > &imgpts, const vector< Vector > &objpts, const Transform &tlocal) |
| geometry_msgs::Pose | FindTransformation (const vector< CvPoint2D32f > &imgpts, const vector< Vector > &objpts, const Transform &tlocal, CHECKERBOARD &cb) |
| void | image_cb (const sensor_msgs::ImageConstPtr &msg) |
| void | image_cb (const sensor_msgs::ImageConstPtr &msg) |
| void | image_cb2 (const sensor_msgs::ImageConstPtr &msg) |
| bool | serviceCallback (checkerboard_detector2::Set::Request &req, checkerboard_detector2::Set::Response &res) |
| virtual | ~CheckerboardDetector () |
| virtual | ~CheckerboardDetector () |
Public Attributes | |
| bool | _active |
| sensor_msgs::CameraInfo | _camInfoMsg |
| sensor_msgs::CvBridge | _cvbridge |
| ros::NodeHandle | _node |
| ros::NodeHandle | _node_private |
| ros::NodeHandle | _node_pub |
| posedetection_msgs::ObjectDetection | _objdetmsg |
| checkerboard_detector2::ObjectDetection | _objdetmsg |
| ros::Publisher | _pubDetection |
| std::vector< ros::Publisher > | _pubPose |
| ros::Publisher | _pubPoseArray |
| ros::ServiceServer | _srvDetect |
| tf::TransformBroadcaster | br_ |
| ros::Subscriber | camInfoSubscriber |
| ros::Subscriber | camInfoSubscriber2 |
| int | display |
| IplImage * | frame |
| string | frame_id |
| ros::Subscriber | imageSubscriber |
| image_transport::Subscriber | imageSubscriber |
| ros::Subscriber | imageSubscriber2 |
| CvMat * | intrinsic_matrix |
| ros::Time | lasttime |
| map< string, int > | maptypes |
| boost::mutex | mutexcalib |
| ros::ServiceServer | service_ |
| vector< CHECKERBOARD > | vcheckers |
| int | verbose |
| vector< string > | vstrtypes |
Static Private Member Functions | |
| template<typename T > | |
| static vector< T > | tokenizevector (const string &s) |
| template<typename T > | |
| static vector< T > | tokenizevector (const string &s) |
Definition at line 48 of file checkerboard_detector.cpp.
| CheckerboardDetector::CheckerboardDetector | ( | ) | [inline] |
Definition at line 90 of file checkerboard_detector.cpp.
| virtual CheckerboardDetector::~CheckerboardDetector | ( | ) | [inline, virtual] |
Definition at line 194 of file checkerboard_detector.cpp.
| CheckerboardDetector::CheckerboardDetector | ( | ) | [inline] |
Definition at line 108 of file checkerboard_detector2.cpp.
| virtual CheckerboardDetector::~CheckerboardDetector | ( | ) | [inline, virtual] |
Definition at line 219 of file checkerboard_detector2.cpp.
| void CheckerboardDetector::activate | ( | bool | active, |
| string | image_topic = std::string(), |
||
| string | camera_info_topic = std::string() |
||
| ) | [inline] |
Definition at line 537 of file checkerboard_detector2.cpp.
| void CheckerboardDetector::caminfo_cb | ( | const sensor_msgs::CameraInfoConstPtr & | msg | ) | [inline] |
Definition at line 209 of file checkerboard_detector.cpp.
| void CheckerboardDetector::caminfo_cb | ( | const sensor_msgs::CameraInfoConstPtr & | msg | ) | [inline] |
Definition at line 231 of file checkerboard_detector2.cpp.
| void CheckerboardDetector::caminfo_cb2 | ( | const sensor_msgs::CameraInfoConstPtr & | msg | ) | [inline] |
Definition at line 219 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 247 of file checkerboard_detector.cpp.
| bool CheckerboardDetector::Detect | ( | checkerboard_detector2::ObjectDetection & | objdetmsg, |
| const sensor_msgs::Image & | imagemsg, | ||
| const sensor_msgs::CameraInfo & | camInfoMsg | ||
| ) | [inline] |
Definition at line 284 of file checkerboard_detector2.cpp.
| bool CheckerboardDetector::detect_cb | ( | posedetection_msgs::Detect::Request & | req, |
| posedetection_msgs::Detect::Response & | res | ||
| ) | [inline] |
Definition at line 242 of file checkerboard_detector.cpp.
| bool CheckerboardDetector::detect_cb | ( | checkerboard_detector2::Detect::Request & | req, |
| checkerboard_detector2::Detect::Response & | res | ||
| ) | [inline] |
Definition at line 276 of file checkerboard_detector2.cpp.
| geometry_msgs::Pose CheckerboardDetector::FindTransformation | ( | const vector< CvPoint2D32f > & | imgpts, |
| const vector< Vector > & | objpts, | ||
| const Transform & | tlocal | ||
| ) | [inline] |
Definition at line 417 of file checkerboard_detector.cpp.
| geometry_msgs::Pose CheckerboardDetector::FindTransformation | ( | const vector< CvPoint2D32f > & | imgpts, |
| const vector< Vector > & | objpts, | ||
| const Transform & | tlocal, | ||
| CHECKERBOARD & | cb | ||
| ) | [inline] |
Definition at line 470 of file checkerboard_detector2.cpp.
| void CheckerboardDetector::image_cb | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [inline] |
Definition at line 235 of file checkerboard_detector.cpp.
| void CheckerboardDetector::image_cb | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [inline] |
Definition at line 245 of file checkerboard_detector2.cpp.
| void CheckerboardDetector::image_cb2 | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [inline] |
Definition at line 225 of file checkerboard_detector.cpp.
| bool CheckerboardDetector::serviceCallback | ( | checkerboard_detector2::Set::Request & | req, |
| checkerboard_detector2::Set::Response & | res | ||
| ) | [inline] |
Definition at line 557 of file checkerboard_detector2.cpp.
| static vector<T> CheckerboardDetector::tokenizevector | ( | const string & | s | ) | [inline, static, private] |
Definition at line 51 of file checkerboard_detector.cpp.
| static vector<T> CheckerboardDetector::tokenizevector | ( | const string & | s | ) | [inline, static, private] |
Definition at line 59 of file checkerboard_detector2.cpp.
Definition at line 103 of file checkerboard_detector2.cpp.
| sensor_msgs::CameraInfo CheckerboardDetector::_camInfoMsg |
Definition at line 68 of file checkerboard_detector.cpp.
| sensor_msgs::CvBridge CheckerboardDetector::_cvbridge |
Definition at line 67 of file checkerboard_detector.cpp.
Definition at line 86 of file checkerboard_detector.cpp.
Definition at line 100 of file checkerboard_detector2.cpp.
Definition at line 101 of file checkerboard_detector2.cpp.
| posedetection_msgs::ObjectDetection CheckerboardDetector::_objdetmsg |
Definition at line 66 of file checkerboard_detector.cpp.
Definition at line 77 of file checkerboard_detector2.cpp.
Definition at line 72 of file checkerboard_detector.cpp.
Definition at line 85 of file checkerboard_detector2.cpp.
Definition at line 84 of file checkerboard_detector2.cpp.
Definition at line 73 of file checkerboard_detector.cpp.
Definition at line 104 of file checkerboard_detector2.cpp.
Definition at line 70 of file checkerboard_detector.cpp.
Definition at line 70 of file checkerboard_detector.cpp.
Definition at line 77 of file checkerboard_detector.cpp.
| IplImage * CheckerboardDetector::frame |
Definition at line 84 of file checkerboard_detector.cpp.
Definition at line 75 of file checkerboard_detector.cpp.
Definition at line 71 of file checkerboard_detector.cpp.
Definition at line 82 of file checkerboard_detector2.cpp.
Definition at line 71 of file checkerboard_detector.cpp.
Definition at line 82 of file checkerboard_detector.cpp.
Definition at line 81 of file checkerboard_detector.cpp.
| map< string, int > CheckerboardDetector::maptypes |
Definition at line 80 of file checkerboard_detector.cpp.
| boost::mutex CheckerboardDetector::mutexcalib |
Definition at line 83 of file checkerboard_detector.cpp.
Definition at line 87 of file checkerboard_detector2.cpp.
Definition at line 78 of file checkerboard_detector.cpp.
Definition at line 77 of file checkerboard_detector.cpp.
| vector< string > CheckerboardDetector::vstrtypes |
Definition at line 79 of file checkerboard_detector.cpp.