Public Member Functions | |
bool | add_new_template (cv::Mat img, std::string typestr, tf::Transform relative_pose, double template_width, double template_height, double theta_step=5.0, double phi_step=5.0) |
void | check_subscribers () |
void | dyn_conf_callback (jsk_perception::point_pose_extractorConfig &config, uint32_t level) |
void | imagefeature_cb (const posedetection_msgs::ImageFeature0DConstPtr &msg) |
void | initialize () |
cv::Mat | make_homography (cv::Mat src, cv::Mat rvec, cv::Mat tvec, double template_width, double template_height, cv::Size &size) |
int | make_warped_images (cv::Mat src, std::vector< cv::Mat > &imgs, std::vector< cv::Mat > &Mvec, double template_width, double template_height, double th_step, double phi_step) |
PointPoseExtractor () | |
bool | settemplate_cb (jsk_perception::SetTemplate::Request &req, jsk_perception::SetTemplate::Response &res) |
virtual | ~PointPoseExtractor () |
Static Public Member Functions | |
static void | cvmousecb (int event, int x, int y, int flags, void *param) |
static void | make_template_from_mousecb (Matching_Template *mt) |
Private Attributes | |
bool | _autosize |
ros::ServiceClient | _client |
image_transport::Publisher | _debug_pub |
double | _distanceratio_threshold |
double | _err_thr |
bool | _initialized |
ros::NodeHandle | _n |
double | _phi_step |
ros::Publisher | _pub |
ros::Publisher | _pub_agg |
ros::Publisher | _pub_pose |
double | _reprojection_threshold |
ros::ServiceServer | _server |
ros::Subscriber | _sub |
double | _th_step |
bool | _viewer |
image_transport::ImageTransport | it |
image_geometry::PinholeCameraModel | pcam |
bool | pnod |
Static Private Attributes | |
static std::vector < Matching_Template * > | _templates |
Definition at line 544 of file point_pose_extractor.cpp.
PointPoseExtractor::PointPoseExtractor | ( | ) | [inline] |
Definition at line 566 of file point_pose_extractor.cpp.
virtual PointPoseExtractor::~PointPoseExtractor | ( | ) | [inline, virtual] |
Definition at line 578 of file point_pose_extractor.cpp.
bool PointPoseExtractor::add_new_template | ( | cv::Mat | img, |
std::string | typestr, | ||
tf::Transform | relative_pose, | ||
double | template_width, | ||
double | template_height, | ||
double | theta_step = 5.0 , |
||
double | phi_step = 5.0 |
||
) | [inline] |
Definition at line 837 of file point_pose_extractor.cpp.
void PointPoseExtractor::check_subscribers | ( | ) | [inline] |
Definition at line 960 of file point_pose_extractor.cpp.
static void PointPoseExtractor::cvmousecb | ( | int | event, |
int | x, | ||
int | y, | ||
int | flags, | ||
void * | param | ||
) | [inline, static] |
Definition at line 659 of file point_pose_extractor.cpp.
void PointPoseExtractor::dyn_conf_callback | ( | jsk_perception::point_pose_extractorConfig & | config, |
uint32_t | level | ||
) | [inline] |
Definition at line 977 of file point_pose_extractor.cpp.
void PointPoseExtractor::imagefeature_cb | ( | const posedetection_msgs::ImageFeature0DConstPtr & | msg | ) | [inline] |
Definition at line 891 of file point_pose_extractor.cpp.
void PointPoseExtractor::initialize | ( | ) | [inline] |
Definition at line 683 of file point_pose_extractor.cpp.
cv::Mat PointPoseExtractor::make_homography | ( | cv::Mat | src, |
cv::Mat | rvec, | ||
cv::Mat | tvec, | ||
double | template_width, | ||
double | template_height, | ||
cv::Size & | size | ||
) | [inline] |
Definition at line 756 of file point_pose_extractor.cpp.
static void PointPoseExtractor::make_template_from_mousecb | ( | Matching_Template * | mt | ) | [inline, static] |
Definition at line 585 of file point_pose_extractor.cpp.
int PointPoseExtractor::make_warped_images | ( | cv::Mat | src, |
std::vector< cv::Mat > & | imgs, | ||
std::vector< cv::Mat > & | Mvec, | ||
double | template_width, | ||
double | template_height, | ||
double | th_step, | ||
double | phi_step | ||
) | [inline] |
Definition at line 798 of file point_pose_extractor.cpp.
bool PointPoseExtractor::settemplate_cb | ( | jsk_perception::SetTemplate::Request & | req, |
jsk_perception::SetTemplate::Response & | res | ||
) | [inline] |
Definition at line 870 of file point_pose_extractor.cpp.
bool PointPoseExtractor::_autosize [private] |
Definition at line 557 of file point_pose_extractor.cpp.
Definition at line 550 of file point_pose_extractor.cpp.
Definition at line 552 of file point_pose_extractor.cpp.
double PointPoseExtractor::_distanceratio_threshold [private] |
Definition at line 554 of file point_pose_extractor.cpp.
double PointPoseExtractor::_err_thr [private] |
Definition at line 558 of file point_pose_extractor.cpp.
bool PointPoseExtractor::_initialized [private] |
Definition at line 562 of file point_pose_extractor.cpp.
ros::NodeHandle PointPoseExtractor::_n [private] |
Definition at line 546 of file point_pose_extractor.cpp.
double PointPoseExtractor::_phi_step [private] |
Definition at line 556 of file point_pose_extractor.cpp.
ros::Publisher PointPoseExtractor::_pub [private] |
Definition at line 551 of file point_pose_extractor.cpp.
ros::Publisher PointPoseExtractor::_pub_agg [private] |
Definition at line 551 of file point_pose_extractor.cpp.
ros::Publisher PointPoseExtractor::_pub_pose [private] |
Definition at line 551 of file point_pose_extractor.cpp.
double PointPoseExtractor::_reprojection_threshold [private] |
Definition at line 553 of file point_pose_extractor.cpp.
Definition at line 549 of file point_pose_extractor.cpp.
ros::Subscriber PointPoseExtractor::_sub [private] |
Definition at line 548 of file point_pose_extractor.cpp.
std::vector< Matching_Template * > PointPoseExtractor::_templates [static, private] |
Definition at line 559 of file point_pose_extractor.cpp.
double PointPoseExtractor::_th_step [private] |
Definition at line 555 of file point_pose_extractor.cpp.
bool PointPoseExtractor::_viewer [private] |
Definition at line 563 of file point_pose_extractor.cpp.
Definition at line 547 of file point_pose_extractor.cpp.
Definition at line 560 of file point_pose_extractor.cpp.
bool PointPoseExtractor::pnod [private] |
Definition at line 561 of file point_pose_extractor.cpp.