Public Member Functions | Static Public Member Functions | Private Attributes | Static Private Attributes
PointPoseExtractor Class Reference

List of all members.

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
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

Detailed Description

Definition at line 505 of file point_pose_extractor.cpp.


Constructor & Destructor Documentation

Definition at line 527 of file point_pose_extractor.cpp.

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

Definition at line 538 of file point_pose_extractor.cpp.


Member Function Documentation

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 798 of file point_pose_extractor.cpp.

Definition at line 914 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 619 of file point_pose_extractor.cpp.

void PointPoseExtractor::dyn_conf_callback ( jsk_perception::point_pose_extractorConfig &  config,
uint32_t  level 
) [inline]

Definition at line 931 of file point_pose_extractor.cpp.

void PointPoseExtractor::imagefeature_cb ( const posedetection_msgs::ImageFeature0DConstPtr &  msg) [inline]

Definition at line 852 of file point_pose_extractor.cpp.

void PointPoseExtractor::initialize ( ) [inline]

Definition at line 643 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 716 of file point_pose_extractor.cpp.

static void PointPoseExtractor::make_template_from_mousecb ( Matching_Template mt) [inline, static]

Definition at line 545 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 759 of file point_pose_extractor.cpp.

bool PointPoseExtractor::settemplate_cb ( jsk_perception::SetTemplate::Request &  req,
jsk_perception::SetTemplate::Response &  res 
) [inline]

Definition at line 831 of file point_pose_extractor.cpp.


Member Data Documentation

Definition at line 518 of file point_pose_extractor.cpp.

Definition at line 511 of file point_pose_extractor.cpp.

Definition at line 513 of file point_pose_extractor.cpp.

Definition at line 515 of file point_pose_extractor.cpp.

double PointPoseExtractor::_err_thr [private]

Definition at line 519 of file point_pose_extractor.cpp.

Definition at line 523 of file point_pose_extractor.cpp.

Definition at line 507 of file point_pose_extractor.cpp.

Definition at line 517 of file point_pose_extractor.cpp.

Definition at line 512 of file point_pose_extractor.cpp.

Definition at line 512 of file point_pose_extractor.cpp.

Definition at line 514 of file point_pose_extractor.cpp.

Definition at line 510 of file point_pose_extractor.cpp.

Definition at line 509 of file point_pose_extractor.cpp.

Definition at line 520 of file point_pose_extractor.cpp.

double PointPoseExtractor::_th_step [private]

Definition at line 516 of file point_pose_extractor.cpp.

Definition at line 524 of file point_pose_extractor.cpp.

Definition at line 508 of file point_pose_extractor.cpp.

Definition at line 521 of file point_pose_extractor.cpp.

bool PointPoseExtractor::pnod [private]

Definition at line 522 of file point_pose_extractor.cpp.


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


jsk_perception
Author(s): Manabu Saito
autogenerated on Mon Oct 6 2014 01:16:59