#include <ros_detector.h>
Definition at line 13 of file ros_detector.h.
checkerboard_pose_estimation::RosDetector::RosDetector | ( | const std::string & | name = ros::this_node::getName() | ) |
Definition at line 6 of file ros_detector.cpp.
bool checkerboard_pose_estimation::RosDetector::detectObject | ( | const sensor_msgs::ImageConstPtr & | image_msg, |
const sensor_msgs::CameraInfoConstPtr & | info_msg, | ||
const tf::Stamped< tf::Pose > & | target_prior, | ||
const tf::Transformer & | transformer, | ||
tf::Stamped< tf::Pose > & | target_pose | ||
) |
Definition at line 77 of file ros_detector.cpp.
Definition at line 20 of file ros_detector.h.
const Detector& checkerboard_pose_estimation::RosDetector::getDetector | ( | ) | const [inline] |
Definition at line 21 of file ros_detector.h.
visual_pose_estimation::PoseEstimator& checkerboard_pose_estimation::RosDetector::getPoseEstimator | ( | ) | [inline] |
Definition at line 23 of file ros_detector.h.
const visual_pose_estimation::PoseEstimator& checkerboard_pose_estimation::RosDetector::getPoseEstimator | ( | ) | const [inline] |
Definition at line 24 of file ros_detector.h.
bool checkerboard_pose_estimation::RosDetector::initFromParameters | ( | const ros::NodeHandle & | nh = ros::NodeHandle("~") | ) |
Definition at line 14 of file ros_detector.cpp.
void checkerboard_pose_estimation::RosDetector::publishDisplayImage | ( | const cv::Mat & | source, |
const std::vector< cv::Point2f > & | corners, | ||
bool | success | ||
) |
Definition at line 124 of file ros_detector.cpp.
image_geometry::PinholeCameraModel checkerboard_pose_estimation::RosDetector::cam_model_ [protected] |
Definition at line 46 of file ros_detector.h.
Definition at line 47 of file ros_detector.h.
sensor_msgs::Image checkerboard_pose_estimation::RosDetector::display_img_ [protected] |
Definition at line 41 of file ros_detector.h.
cv::Mat checkerboard_pose_estimation::RosDetector::display_img_cv_ [protected] |
Definition at line 42 of file ros_detector.h.
Definition at line 40 of file ros_detector.h.
Definition at line 35 of file ros_detector.h.
Definition at line 43 of file ros_detector.h.
std::string checkerboard_pose_estimation::RosDetector::name_ [protected] |
Definition at line 36 of file ros_detector.h.
Definition at line 34 of file ros_detector.h.
visual_pose_estimation::PoseEstimator checkerboard_pose_estimation::RosDetector::pose_estimator_ [protected] |
Definition at line 48 of file ros_detector.h.
Definition at line 50 of file ros_detector.h.
Definition at line 51 of file ros_detector.h.
Definition at line 39 of file ros_detector.h.