Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
jsk_pcl_ros::FindObjectOnPlane Class Reference

#include <find_object_on_plane.h>

Inheritance diagram for jsk_pcl_ros::FindObjectOnPlane:
Inheritance graph
[legend]

List of all members.

Public Types

typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
sensor_msgs::CameraInfo,
pcl_msgs::ModelCoefficients > 
SyncPolicy

Public Member Functions

 FindObjectOnPlane ()

Protected Member Functions

virtual double drawAngle (cv::Mat &out_image, const cv::Point2f &test_point, const double angle, const double max_x, const double max_y, const image_geometry::PinholeCameraModel &model, const jsk_pcl_ros::Plane::Ptr &plane, cv::Scalar color)
virtual void find (const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::CameraInfo::ConstPtr &info_msg, const pcl_msgs::ModelCoefficients::ConstPtr &polygon_3d_coefficient_msg)
virtual void generateAngles (const cv::Mat &blob_image, const cv::Point2f &test_point, std::vector< double > &angles, std::vector< double > &max_x, std::vector< double > &max_y, const image_geometry::PinholeCameraModel &model, const jsk_pcl_ros::Plane::Ptr &plane)
virtual void generateStartPoints (const cv::Point2f &point_2d, const image_geometry::PinholeCameraModel &model, const pcl::ModelCoefficients::Ptr &coefficients, std::vector< cv::Point3f > &search_points_3d, std::vector< cv::Point2f > &search_points_2d)
virtual cv::Point2d getUyEnd (const cv::Point2d &ux_start, const cv::Point2d &ux_end, const image_geometry::PinholeCameraModel &model, const jsk_pcl_ros::Plane::Ptr &plane)
virtual void onInit ()
Eigen::Vector3f rayPlaneInteersect (const cv::Point3d &ray, const jsk_pcl_ros::Plane::Ptr &plane)
virtual void subscribe ()
virtual void unsubscribe ()

Protected Attributes

ros::Publisher pub_min_area_rect_image_
message_filters::Subscriber
< pcl_msgs::ModelCoefficients > 
sub_coefficients_
message_filters::Subscriber
< sensor_msgs::Image > 
sub_image_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
sub_info_
boost::shared_ptr
< message_filters::Synchronizer
< SyncPolicy > > 
sync_

Detailed Description

Definition at line 54 of file find_object_on_plane.h.


Member Typedef Documentation

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo, pcl_msgs::ModelCoefficients > jsk_pcl_ros::FindObjectOnPlane::SyncPolicy

Definition at line 60 of file find_object_on_plane.h.


Constructor & Destructor Documentation

Definition at line 62 of file find_object_on_plane.h.


Member Function Documentation

double jsk_pcl_ros::FindObjectOnPlane::drawAngle ( cv::Mat &  out_image,
const cv::Point2f &  test_point,
const double  angle,
const double  max_x,
const double  max_y,
const image_geometry::PinholeCameraModel model,
const jsk_pcl_ros::Plane::Ptr plane,
cv::Scalar  color 
) [protected, virtual]

Definition at line 237 of file find_object_on_plane_nodelet.cpp.

void jsk_pcl_ros::FindObjectOnPlane::find ( const sensor_msgs::Image::ConstPtr &  image_msg,
const sensor_msgs::CameraInfo::ConstPtr &  info_msg,
const pcl_msgs::ModelCoefficients::ConstPtr &  polygon_3d_coefficient_msg 
) [protected, virtual]

Definition at line 67 of file find_object_on_plane_nodelet.cpp.

void jsk_pcl_ros::FindObjectOnPlane::generateAngles ( const cv::Mat &  blob_image,
const cv::Point2f &  test_point,
std::vector< double > &  angles,
std::vector< double > &  max_x,
std::vector< double > &  max_y,
const image_geometry::PinholeCameraModel model,
const jsk_pcl_ros::Plane::Ptr plane 
) [protected, virtual]

Definition at line 150 of file find_object_on_plane_nodelet.cpp.

void jsk_pcl_ros::FindObjectOnPlane::generateStartPoints ( const cv::Point2f &  point_2d,
const image_geometry::PinholeCameraModel model,
const pcl::ModelCoefficients::Ptr &  coefficients,
std::vector< cv::Point3f > &  search_points_3d,
std::vector< cv::Point2f > &  search_points_2d 
) [protected, virtual]

Definition at line 262 of file find_object_on_plane_nodelet.cpp.

cv::Point2d jsk_pcl_ros::FindObjectOnPlane::getUyEnd ( const cv::Point2d &  ux_start,
const cv::Point2d &  ux_end,
const image_geometry::PinholeCameraModel model,
const jsk_pcl_ros::Plane::Ptr plane 
) [protected, virtual]

Definition at line 217 of file find_object_on_plane_nodelet.cpp.

void jsk_pcl_ros::FindObjectOnPlane::onInit ( void  ) [protected, virtual]

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 43 of file find_object_on_plane_nodelet.cpp.

Eigen::Vector3f jsk_pcl_ros::FindObjectOnPlane::rayPlaneInteersect ( const cv::Point3d &  ray,
const jsk_pcl_ros::Plane::Ptr plane 
) [protected]

Definition at line 207 of file find_object_on_plane_nodelet.cpp.

void jsk_pcl_ros::FindObjectOnPlane::subscribe ( ) [protected, virtual]
void jsk_pcl_ros::FindObjectOnPlane::unsubscribe ( ) [protected, virtual]

Member Data Documentation

Definition at line 104 of file find_object_on_plane.h.

Definition at line 103 of file find_object_on_plane.h.

Definition at line 101 of file find_object_on_plane.h.

Definition at line 102 of file find_object_on_plane.h.

Definition at line 100 of file find_object_on_plane.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:49