Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Static Protected Member Functions | Protected Attributes | List of all members
jsk_perception::PointPoseExtractor Class Reference

#include <point_pose_extractor.h>

Inheritance diagram for jsk_perception::PointPoseExtractor:
Inheritance graph
[legend]

Public Types

typedef jsk_perception::point_pose_extractorConfig Config
 

Public Member Functions

 PointPoseExtractor ()
 
virtual ~PointPoseExtractor ()
 

Public Attributes

std::vector< Matching_Template * > _templates
 

Protected Member Functions

virtual bool add_new_template (cv::Mat img, std::string typestr, tf::Transform relative_pose, double template_width, double template_height, double theta_step, double phi_step)
 
virtual void dyn_conf_callback (Config &config, uint32_t level)
 
virtual void imagefeature_cb (const posedetection_msgs::ImageFeature0DConstPtr &msg)
 
virtual void initialize ()
 
virtual cv::Mat make_homography (cv::Mat src, cv::Mat rvec, cv::Mat tvec, double template_width, double template_height, cv::Size &size)
 
virtual 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)
 
virtual void onInit ()
 
virtual bool settemplate_cb (jsk_perception::SetTemplate::Request &req, jsk_perception::SetTemplate::Response &res)
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 

Static Protected Member Functions

static void cvmousecb (int event, int x, int y, int flags, void *param)
 
static void make_template_from_mousecb (PointPoseExtractor *ppe)
 

Protected Attributes

bool _autosize
 
tf::TransformBroadcaster _br
 
std::string _child_frame_id
 
ros::ServiceClient _client
 
image_transport::Publisher _debug_pub
 
double _distanceratio_threshold
 
double _err_thr
 
bool _first_sample_change
 
bool _initialized
 
ros::NodeHandle _n
 
double _phi_step
 
ros::Publisher _pub
 
ros::Publisher _pub_agg
 
ros::Publisher _pub_pose
 
bool _publish_tf
 
double _reprojection_threshold
 
ros::ServiceServer _server
 
ros::Subscriber _sub
 
double _th_step
 
bool _viewer
 
image_transport::ImageTransportit
 
image_geometry::PinholeCameraModel pcam
 
bool pnod
 

Detailed Description

Definition at line 556 of file point_pose_extractor.h.

Member Typedef Documentation

◆ Config

typedef jsk_perception::point_pose_extractorConfig jsk_perception::PointPoseExtractor::Config

Definition at line 560 of file point_pose_extractor.h.

Constructor & Destructor Documentation

◆ PointPoseExtractor()

jsk_perception::PointPoseExtractor::PointPoseExtractor ( )
inline

Definition at line 561 of file point_pose_extractor.h.

◆ ~PointPoseExtractor()

jsk_perception::PointPoseExtractor::~PointPoseExtractor ( )
virtual

Definition at line 72 of file point_pose_extractor.cpp.

Member Function Documentation

◆ add_new_template()

bool jsk_perception::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 
)
protectedvirtual

Definition at line 234 of file point_pose_extractor.cpp.

◆ cvmousecb()

static void jsk_perception::PointPoseExtractor::cvmousecb ( int  event,
int  x,
int  y,
int  flags,
void *  param 
)
inlinestaticprotected

Definition at line 604 of file point_pose_extractor.h.

◆ dyn_conf_callback()

void jsk_perception::PointPoseExtractor::dyn_conf_callback ( Config config,
uint32_t  level 
)
protectedvirtual

Definition at line 405 of file point_pose_extractor.cpp.

◆ imagefeature_cb()

void jsk_perception::PointPoseExtractor::imagefeature_cb ( const posedetection_msgs::ImageFeature0DConstPtr &  msg)
protectedvirtual

Definition at line 289 of file point_pose_extractor.cpp.

◆ initialize()

void jsk_perception::PointPoseExtractor::initialize ( )
protectedvirtual

Definition at line 79 of file point_pose_extractor.cpp.

◆ make_homography()

cv::Mat jsk_perception::PointPoseExtractor::make_homography ( cv::Mat  src,
cv::Mat  rvec,
cv::Mat  tvec,
double  template_width,
double  template_height,
cv::Size &  size 
)
protectedvirtual

Definition at line 151 of file point_pose_extractor.cpp.

◆ make_template_from_mousecb()

static void jsk_perception::PointPoseExtractor::make_template_from_mousecb ( PointPoseExtractor ppe)
inlinestaticprotected

Definition at line 627 of file point_pose_extractor.h.

◆ make_warped_images()

int jsk_perception::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 
)
protectedvirtual

Definition at line 193 of file point_pose_extractor.cpp.

◆ onInit()

void jsk_perception::PointPoseExtractor::onInit ( )
protectedvirtual

Definition at line 370 of file point_pose_extractor.cpp.

◆ settemplate_cb()

bool jsk_perception::PointPoseExtractor::settemplate_cb ( jsk_perception::SetTemplate::Request &  req,
jsk_perception::SetTemplate::Response &  res 
)
protectedvirtual

Definition at line 269 of file point_pose_extractor.cpp.

◆ subscribe()

void jsk_perception::PointPoseExtractor::subscribe ( )
protectedvirtual

Definition at line 393 of file point_pose_extractor.cpp.

◆ unsubscribe()

void jsk_perception::PointPoseExtractor::unsubscribe ( )
protectedvirtual

Definition at line 399 of file point_pose_extractor.cpp.

Member Data Documentation

◆ _autosize

bool jsk_perception::PointPoseExtractor::_autosize
protected

Definition at line 577 of file point_pose_extractor.h.

◆ _br

tf::TransformBroadcaster jsk_perception::PointPoseExtractor::_br
protected

Definition at line 570 of file point_pose_extractor.h.

◆ _child_frame_id

std::string jsk_perception::PointPoseExtractor::_child_frame_id
protected

Definition at line 584 of file point_pose_extractor.h.

◆ _client

ros::ServiceClient jsk_perception::PointPoseExtractor::_client
protected

Definition at line 568 of file point_pose_extractor.h.

◆ _debug_pub

image_transport::Publisher jsk_perception::PointPoseExtractor::_debug_pub
protected

Definition at line 571 of file point_pose_extractor.h.

◆ _distanceratio_threshold

double jsk_perception::PointPoseExtractor::_distanceratio_threshold
protected

Definition at line 574 of file point_pose_extractor.h.

◆ _err_thr

double jsk_perception::PointPoseExtractor::_err_thr
protected

Definition at line 578 of file point_pose_extractor.h.

◆ _first_sample_change

bool jsk_perception::PointPoseExtractor::_first_sample_change
protected

Definition at line 572 of file point_pose_extractor.h.

◆ _initialized

bool jsk_perception::PointPoseExtractor::_initialized
protected

Definition at line 581 of file point_pose_extractor.h.

◆ _n

ros::NodeHandle jsk_perception::PointPoseExtractor::_n
protected

Definition at line 564 of file point_pose_extractor.h.

◆ _phi_step

double jsk_perception::PointPoseExtractor::_phi_step
protected

Definition at line 576 of file point_pose_extractor.h.

◆ _pub

ros::Publisher jsk_perception::PointPoseExtractor::_pub
protected

Definition at line 569 of file point_pose_extractor.h.

◆ _pub_agg

ros::Publisher jsk_perception::PointPoseExtractor::_pub_agg
protected

Definition at line 569 of file point_pose_extractor.h.

◆ _pub_pose

ros::Publisher jsk_perception::PointPoseExtractor::_pub_pose
protected

Definition at line 569 of file point_pose_extractor.h.

◆ _publish_tf

bool jsk_perception::PointPoseExtractor::_publish_tf
protected

Definition at line 583 of file point_pose_extractor.h.

◆ _reprojection_threshold

double jsk_perception::PointPoseExtractor::_reprojection_threshold
protected

Definition at line 573 of file point_pose_extractor.h.

◆ _server

ros::ServiceServer jsk_perception::PointPoseExtractor::_server
protected

Definition at line 567 of file point_pose_extractor.h.

◆ _sub

ros::Subscriber jsk_perception::PointPoseExtractor::_sub
protected

Definition at line 566 of file point_pose_extractor.h.

◆ _templates

std::vector<Matching_Template *> jsk_perception::PointPoseExtractor::_templates

Definition at line 559 of file point_pose_extractor.h.

◆ _th_step

double jsk_perception::PointPoseExtractor::_th_step
protected

Definition at line 575 of file point_pose_extractor.h.

◆ _viewer

bool jsk_perception::PointPoseExtractor::_viewer
protected

Definition at line 582 of file point_pose_extractor.h.

◆ it

image_transport::ImageTransport* jsk_perception::PointPoseExtractor::it
protected

Definition at line 565 of file point_pose_extractor.h.

◆ pcam

image_geometry::PinholeCameraModel jsk_perception::PointPoseExtractor::pcam
protected

Definition at line 579 of file point_pose_extractor.h.

◆ pnod

bool jsk_perception::PointPoseExtractor::pnod
protected

Definition at line 580 of file point_pose_extractor.h.


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


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17