Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
jsk_perception::ProjectImagePoint Class Reference

#include <project_image_point.h>

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

List of all members.

Public Types

typedef ProjectImagePointConfig Config
typedef boost::shared_ptr
< ProjectImagePoint
Ptr

Public Member Functions

 ProjectImagePoint ()

Protected Member Functions

virtual void cameraInfoCallback (const sensor_msgs::CameraInfo::ConstPtr &msg)
virtual void configCallback (Config &config, uint32_t level)
virtual void onInit ()
virtual void project (const geometry_msgs::PointStamped::ConstPtr &msg)
virtual void subscribe ()
virtual void unsubscribe ()

Protected Attributes

sensor_msgs::CameraInfo::ConstPtr camera_info_
boost::mutex mutex_
ros::Publisher pub_
ros::Publisher pub_vector_
boost::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
ros::Subscriber sub_
ros::Subscriber sub_camera_info_
double z_

Detailed Description

Definition at line 52 of file project_image_point.h.


Member Typedef Documentation

typedef ProjectImagePointConfig jsk_perception::ProjectImagePoint::Config

Definition at line 56 of file project_image_point.h.

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 55 of file project_image_point.h.


Constructor & Destructor Documentation

Definition at line 57 of file project_image_point.h.


Member Function Documentation

void jsk_perception::ProjectImagePoint::cameraInfoCallback ( const sensor_msgs::CameraInfo::ConstPtr &  msg) [protected, virtual]

Definition at line 73 of file project_image_point.cpp.

void jsk_perception::ProjectImagePoint::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]

Definition at line 67 of file project_image_point.cpp.

void jsk_perception::ProjectImagePoint::onInit ( ) [protected, virtual]

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 40 of file project_image_point.cpp.

void jsk_perception::ProjectImagePoint::project ( const geometry_msgs::PointStamped::ConstPtr &  msg) [protected, virtual]

Definition at line 80 of file project_image_point.cpp.

void jsk_perception::ProjectImagePoint::subscribe ( ) [protected, virtual]

Implements jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 53 of file project_image_point.cpp.

void jsk_perception::ProjectImagePoint::unsubscribe ( ) [protected, virtual]

Implements jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 61 of file project_image_point.cpp.


Member Data Documentation

sensor_msgs::CameraInfo::ConstPtr jsk_perception::ProjectImagePoint::camera_info_ [protected]

Definition at line 72 of file project_image_point.h.

Definition at line 67 of file project_image_point.h.

Definition at line 70 of file project_image_point.h.

Definition at line 71 of file project_image_point.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_perception::ProjectImagePoint::srv_ [protected]

Definition at line 73 of file project_image_point.h.

Definition at line 68 of file project_image_point.h.

Definition at line 69 of file project_image_point.h.

Definition at line 74 of file project_image_point.h.


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


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:36:16