Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::IntermittentImageAnnotator Class Reference

#include <intermittent_image_annotator.h>

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

Public Types

typedef boost::shared_ptr< IntermittentImageAnnotatorPtr
 

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 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::Ptrsnapshot_buffer_
 
bool store_pointcloud_
 

Detailed Description

Definition at line 105 of file intermittent_image_annotator.h.

Member Typedef Documentation

◆ Ptr

Definition at line 108 of file intermittent_image_annotator.h.

Constructor & Destructor Documentation

◆ IntermittentImageAnnotator()

jsk_pcl_ros::IntermittentImageAnnotator::IntermittentImageAnnotator ( )
inline

Definition at line 109 of file intermittent_image_annotator.h.

Member Function Documentation

◆ cameraCallback()

void jsk_pcl_ros::IntermittentImageAnnotator::cameraCallback ( const sensor_msgs::Image::ConstPtr &  image_msg,
const sensor_msgs::CameraInfo::ConstPtr &  info_msg 
)
protectedvirtual

Definition at line 288 of file intermittent_image_annotator_nodelet.cpp.

◆ clearCallback()

bool jsk_pcl_ros::IntermittentImageAnnotator::clearCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)
protectedvirtual

Definition at line 416 of file intermittent_image_annotator_nodelet.cpp.

◆ cloudCallback()

void jsk_pcl_ros::IntermittentImageAnnotator::cloudCallback ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg)
protectedvirtual

Definition at line 281 of file intermittent_image_annotator_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::IntermittentImageAnnotator::onInit ( )
protectedvirtual

Definition at line 47 of file intermittent_image_annotator_nodelet.cpp.

◆ publishCroppedPointCloud()

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 
)
protectedvirtual

Definition at line 224 of file intermittent_image_annotator_nodelet.cpp.

◆ rectCallback()

void jsk_pcl_ros::IntermittentImageAnnotator::rectCallback ( const geometry_msgs::PolygonStamped::ConstPtr &  rect)
protectedvirtual

Definition at line 103 of file intermittent_image_annotator_nodelet.cpp.

◆ requestCallback()

bool jsk_pcl_ros::IntermittentImageAnnotator::requestCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)
protectedvirtual

Definition at line 425 of file intermittent_image_annotator_nodelet.cpp.

◆ shutterCallback()

bool jsk_pcl_ros::IntermittentImageAnnotator::shutterCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)
protectedvirtual

Definition at line 332 of file intermittent_image_annotator_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros::IntermittentImageAnnotator::subscribe ( )
protectedvirtual

Definition at line 95 of file intermittent_image_annotator_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::IntermittentImageAnnotator::unsubscribe ( )
protectedvirtual

Definition at line 99 of file intermittent_image_annotator_nodelet.cpp.

◆ waitForNextImage()

void jsk_pcl_ros::IntermittentImageAnnotator::waitForNextImage ( )
protectedvirtual

Definition at line 317 of file intermittent_image_annotator_nodelet.cpp.

Member Data Documentation

◆ clear_service_

ros::ServiceServer jsk_pcl_ros::IntermittentImageAnnotator::clear_service_
protected

Definition at line 153 of file intermittent_image_annotator.h.

◆ cloud_sub_

ros::Subscriber jsk_pcl_ros::IntermittentImageAnnotator::cloud_sub_
protected

Definition at line 151 of file intermittent_image_annotator.h.

◆ fixed_frame_id_

std::string jsk_pcl_ros::IntermittentImageAnnotator::fixed_frame_id_
protected

Definition at line 168 of file intermittent_image_annotator.h.

◆ image_pub_

image_transport::Publisher jsk_pcl_ros::IntermittentImageAnnotator::image_pub_
protected

Definition at line 147 of file intermittent_image_annotator.h.

◆ image_sub_

image_transport::CameraSubscriber jsk_pcl_ros::IntermittentImageAnnotator::image_sub_
protected

Definition at line 148 of file intermittent_image_annotator.h.

◆ keep_organized_

bool jsk_pcl_ros::IntermittentImageAnnotator::keep_organized_
protected

Definition at line 163 of file intermittent_image_annotator.h.

◆ last_publish_time_

ros::Time jsk_pcl_ros::IntermittentImageAnnotator::last_publish_time_
protected

Definition at line 146 of file intermittent_image_annotator.h.

◆ latest_camera_info_msg_

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

Definition at line 160 of file intermittent_image_annotator.h.

◆ latest_cloud_msg_

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

Definition at line 161 of file intermittent_image_annotator.h.

◆ latest_image_msg_

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

Definition at line 159 of file intermittent_image_annotator.h.

◆ listener_

tf::TransformListener* jsk_pcl_ros::IntermittentImageAnnotator::listener_
protected

Definition at line 144 of file intermittent_image_annotator.h.

◆ max_image_buffer_

int jsk_pcl_ros::IntermittentImageAnnotator::max_image_buffer_
protected

Definition at line 167 of file intermittent_image_annotator.h.

◆ mutex_

boost::mutex jsk_pcl_ros::IntermittentImageAnnotator::mutex_
protected

Definition at line 149 of file intermittent_image_annotator.h.

◆ pub_cloud_

ros::Publisher jsk_pcl_ros::IntermittentImageAnnotator::pub_cloud_
protected

Definition at line 158 of file intermittent_image_annotator.h.

◆ pub_marker_

ros::Publisher jsk_pcl_ros::IntermittentImageAnnotator::pub_marker_
protected

Definition at line 157 of file intermittent_image_annotator.h.

◆ pub_pose_

ros::Publisher jsk_pcl_ros::IntermittentImageAnnotator::pub_pose_
protected

Definition at line 155 of file intermittent_image_annotator.h.

◆ pub_roi_

ros::Publisher jsk_pcl_ros::IntermittentImageAnnotator::pub_roi_
protected

Definition at line 156 of file intermittent_image_annotator.h.

◆ rate_

double jsk_pcl_ros::IntermittentImageAnnotator::rate_
protected

Definition at line 145 of file intermittent_image_annotator.h.

◆ rect_sub_

ros::Subscriber jsk_pcl_ros::IntermittentImageAnnotator::rect_sub_
protected

Definition at line 150 of file intermittent_image_annotator.h.

◆ request_service_

ros::ServiceServer jsk_pcl_ros::IntermittentImageAnnotator::request_service_
protected

Definition at line 154 of file intermittent_image_annotator.h.

◆ shutter_service_

ros::ServiceServer jsk_pcl_ros::IntermittentImageAnnotator::shutter_service_
protected

Definition at line 152 of file intermittent_image_annotator.h.

◆ snapshot_buffer_

boost::circular_buffer<SnapshotInformation::Ptr> jsk_pcl_ros::IntermittentImageAnnotator::snapshot_buffer_
protected

Definition at line 169 of file intermittent_image_annotator.h.

◆ store_pointcloud_

bool jsk_pcl_ros::IntermittentImageAnnotator::store_pointcloud_
protected

Definition at line 162 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 Tue Jan 7 2025 04:05:46