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

#include <intermittent_image_annotator.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< IntermittentImageAnnotator
Ptr

Public Member Functions

 IntermittentImageAnnotator ()

Protected Member Functions

virtual void cameraCallback (const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::CameraInfo::ConstPtr &info_msg)
virtual bool clearCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
virtual void cloudCallback (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
virtual void onInit ()
virtual void publishCroppedPointCloud (pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud, const cv::Point3d &A, const cv::Point3d &B, const cv::Point3d &C, const cv::Point3d &D, const Eigen::Affine3d &pose)
virtual void rectCallback (const geometry_msgs::PolygonStamped::ConstPtr &rect)
virtual bool requestCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
virtual bool shutterCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
virtual void subscribe ()
virtual void unsubscribe ()
virtual void updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
virtual void waitForNextImage ()

Protected Attributes

ros::ServiceServer clear_service_
ros::Subscriber cloud_sub_
std::string fixed_frame_id_
image_transport::Publisher image_pub_
image_transport::CameraSubscriber image_sub_
bool keep_organized_
ros::Time last_publish_time_
sensor_msgs::CameraInfo::ConstPtr latest_camera_info_msg_
sensor_msgs::PointCloud2::ConstPtr latest_cloud_msg_
sensor_msgs::Image::ConstPtr latest_image_msg_
tf::TransformListenerlistener_
int max_image_buffer_
boost::mutex mutex_
ros::Publisher pub_cloud_
ros::Publisher pub_marker_
ros::Publisher pub_pose_
ros::Publisher pub_roi_
double rate_
ros::Subscriber rect_sub_
ros::ServiceServer request_service_
ros::ServiceServer shutter_service_
boost::circular_buffer
< SnapshotInformation::Ptr
snapshot_buffer_
bool store_pointcloud_

Detailed Description

Definition at line 73 of file intermittent_image_annotator.h.


Member Typedef Documentation

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 76 of file intermittent_image_annotator.h.


Constructor & Destructor Documentation

Definition at line 77 of file intermittent_image_annotator.h.


Member Function Documentation

void jsk_pcl_ros::IntermittentImageAnnotator::cameraCallback ( const sensor_msgs::Image::ConstPtr &  image_msg,
const sensor_msgs::CameraInfo::ConstPtr &  info_msg 
) [protected, virtual]

Definition at line 283 of file intermittent_image_annotator_nodelet.cpp.

bool jsk_pcl_ros::IntermittentImageAnnotator::clearCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [protected, virtual]

Definition at line 411 of file intermittent_image_annotator_nodelet.cpp.

void jsk_pcl_ros::IntermittentImageAnnotator::cloudCallback ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg) [protected, virtual]

Definition at line 276 of file intermittent_image_annotator_nodelet.cpp.

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

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 47 of file intermittent_image_annotator_nodelet.cpp.

void jsk_pcl_ros::IntermittentImageAnnotator::publishCroppedPointCloud ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr  cloud,
const cv::Point3d &  A,
const cv::Point3d &  B,
const cv::Point3d &  C,
const cv::Point3d &  D,
const Eigen::Affine3d &  pose 
) [protected, virtual]

Definition at line 219 of file intermittent_image_annotator_nodelet.cpp.

void jsk_pcl_ros::IntermittentImageAnnotator::rectCallback ( const geometry_msgs::PolygonStamped::ConstPtr &  rect) [protected, virtual]

Definition at line 102 of file intermittent_image_annotator_nodelet.cpp.

bool jsk_pcl_ros::IntermittentImageAnnotator::requestCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [protected, virtual]

Definition at line 420 of file intermittent_image_annotator_nodelet.cpp.

bool jsk_pcl_ros::IntermittentImageAnnotator::shutterCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [protected, virtual]

Definition at line 327 of file intermittent_image_annotator_nodelet.cpp.

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 446 of file intermittent_image_annotator_nodelet.cpp.

Definition at line 312 of file intermittent_image_annotator_nodelet.cpp.


Member Data Documentation

Definition at line 123 of file intermittent_image_annotator.h.

Definition at line 121 of file intermittent_image_annotator.h.

Definition at line 138 of file intermittent_image_annotator.h.

Definition at line 117 of file intermittent_image_annotator.h.

Definition at line 118 of file intermittent_image_annotator.h.

Definition at line 133 of file intermittent_image_annotator.h.

Definition at line 116 of file intermittent_image_annotator.h.

sensor_msgs::CameraInfo::ConstPtr jsk_pcl_ros::IntermittentImageAnnotator::latest_camera_info_msg_ [protected]

Definition at line 130 of file intermittent_image_annotator.h.

sensor_msgs::PointCloud2::ConstPtr jsk_pcl_ros::IntermittentImageAnnotator::latest_cloud_msg_ [protected]

Definition at line 131 of file intermittent_image_annotator.h.

sensor_msgs::Image::ConstPtr jsk_pcl_ros::IntermittentImageAnnotator::latest_image_msg_ [protected]

Definition at line 129 of file intermittent_image_annotator.h.

Definition at line 114 of file intermittent_image_annotator.h.

Definition at line 137 of file intermittent_image_annotator.h.

Definition at line 119 of file intermittent_image_annotator.h.

Definition at line 128 of file intermittent_image_annotator.h.

Definition at line 127 of file intermittent_image_annotator.h.

Definition at line 125 of file intermittent_image_annotator.h.

Definition at line 126 of file intermittent_image_annotator.h.

Definition at line 115 of file intermittent_image_annotator.h.

Definition at line 120 of file intermittent_image_annotator.h.

Definition at line 124 of file intermittent_image_annotator.h.

Definition at line 122 of file intermittent_image_annotator.h.

Definition at line 139 of file intermittent_image_annotator.h.

Definition at line 132 of file intermittent_image_annotator.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