$search

image_algos::PCDToImageProjector Class Reference

#include <pcd_to_image_projector_algo.h>

Inheritance diagram for image_algos::PCDToImageProjector:
Inheritance graph
[legend]

List of all members.

Public Types

typedef sensor_msgs::Image InputType
typedef sensor_msgs::PointCloud InputTypeII
typedef IplImage * OutputType

Public Member Functions

void init (ros::NodeHandle &)
OutputType output ()
 PCDToImageProjector ()
void post ()
void pre ()
std::string process (geometry_msgs::Polygon &cloud_in, IplImage *image)
std::string process (sensor_msgs::PointCloud &cloud_in, IplImage *image)
void project_3D_point (const double &x, const double &y, const double &z, int &row, int &column)
std::vector< std::string > provides ()
std::vector< std::string > requires ()

Static Public Member Functions

static std::string default_input_topic ()
static std::string default_node_name ()
static std::string default_output_topic ()

Public Attributes

sensor_msgs::CvBridge bridge_
std::string child_
boost::mutex cloud_lock_
std::vector
< sensor_msgs::PointCloud
cloud_queue_
ros::Subscriber cloud_sub_
double focal_length_
image_transport::Publisher image_pub_
image_transport::Subscriber image_sub_
std::string input_cloud_topic_
std::string input_image_topic_
std::string interim_
ros::NodeHandle nh_
std::string origin_
std::string output_cluster_topic_
std::string output_image_topic_
double pix_size_x_
double pix_size_y_
double proj_center_x_
double proj_center_y_
OutputType subimage_
tf::TransformListener tf_listener_

Detailed Description

Definition at line 54 of file pcd_to_image_projector_algo.h.


Member Typedef Documentation

Reimplemented from image_algos::ImageAlgo.

Definition at line 59 of file pcd_to_image_projector_algo.h.

Definition at line 61 of file pcd_to_image_projector_algo.h.

Reimplemented from image_algos::ImageAlgo.

Definition at line 63 of file pcd_to_image_projector_algo.h.


Constructor & Destructor Documentation

image_algos::PCDToImageProjector::PCDToImageProjector (  )  [inline]

Definition at line 57 of file pcd_to_image_projector_algo.h.


Member Function Documentation

static std::string image_algos::PCDToImageProjector::default_input_topic (  )  [inline, static]

Reimplemented from image_algos::ImageAlgo.

Definition at line 65 of file pcd_to_image_projector_algo.h.

static std::string image_algos::PCDToImageProjector::default_node_name (  )  [inline, static]

Reimplemented from image_algos::ImageAlgo.

Definition at line 71 of file pcd_to_image_projector_algo.h.

static std::string image_algos::PCDToImageProjector::default_output_topic (  )  [inline, static]

Reimplemented from image_algos::ImageAlgo.

Definition at line 68 of file pcd_to_image_projector_algo.h.

void PCDToImageProjector::init ( ros::NodeHandle nh  )  [virtual]

Implements image_algos::ImageAlgo.

Definition at line 37 of file pcd_to_image_projector_algo.cpp.

PCDToImageProjector::OutputType PCDToImageProjector::output (  ) 

Reimplemented from image_algos::ImageAlgo.

Definition at line 276 of file pcd_to_image_projector_algo.cpp.

void PCDToImageProjector::post (  )  [virtual]

Implements image_algos::ImageAlgo.

Definition at line 63 of file pcd_to_image_projector_algo.cpp.

void PCDToImageProjector::pre (  )  [virtual]

Implements image_algos::ImageAlgo.

Definition at line 57 of file pcd_to_image_projector_algo.cpp.

std::string PCDToImageProjector::process ( geometry_msgs::Polygon cloud_in,
IplImage *  image 
)

Definition at line 182 of file pcd_to_image_projector_algo.cpp.

std::string PCDToImageProjector::process ( sensor_msgs::PointCloud cloud_in,
IplImage *  image 
)

Definition at line 99 of file pcd_to_image_projector_algo.cpp.

void PCDToImageProjector::project_3D_point ( const double &  x,
const double &  y,
const double &  z,
int &  row,
int &  column 
)

Definition at line 81 of file pcd_to_image_projector_algo.cpp.

std::vector< std::string > PCDToImageProjector::provides (  )  [virtual]

Implements image_algos::ImageAlgo.

Definition at line 76 of file pcd_to_image_projector_algo.cpp.

std::vector< std::string > PCDToImageProjector::requires (  )  [virtual]

Implements image_algos::ImageAlgo.

Definition at line 70 of file pcd_to_image_projector_algo.cpp.


Member Data Documentation

Definition at line 95 of file pcd_to_image_projector_algo.h.

Definition at line 104 of file pcd_to_image_projector_algo.h.

Definition at line 105 of file pcd_to_image_projector_algo.h.

Definition at line 106 of file pcd_to_image_projector_algo.h.

Definition at line 90 of file pcd_to_image_projector_algo.h.

Definition at line 100 of file pcd_to_image_projector_algo.h.

Definition at line 88 of file pcd_to_image_projector_algo.h.

Definition at line 89 of file pcd_to_image_projector_algo.h.

Definition at line 98 of file pcd_to_image_projector_algo.h.

Definition at line 98 of file pcd_to_image_projector_algo.h.

Definition at line 104 of file pcd_to_image_projector_algo.h.

Definition at line 87 of file pcd_to_image_projector_algo.h.

Definition at line 104 of file pcd_to_image_projector_algo.h.

Definition at line 98 of file pcd_to_image_projector_algo.h.

Definition at line 98 of file pcd_to_image_projector_algo.h.

Definition at line 100 of file pcd_to_image_projector_algo.h.

Definition at line 100 of file pcd_to_image_projector_algo.h.

Definition at line 100 of file pcd_to_image_projector_algo.h.

Definition at line 100 of file pcd_to_image_projector_algo.h.

Definition at line 97 of file pcd_to_image_projector_algo.h.

Definition at line 92 of file pcd_to_image_projector_algo.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


image_algos
Author(s): Dejan Pangercic
autogenerated on Tue Dec 4 10:08:33 2012