#include <intermittent_image_annotator.h>
◆ Ptr
◆ IntermittentImageAnnotator()
jsk_pcl_ros::IntermittentImageAnnotator::IntermittentImageAnnotator |
( |
| ) |
|
|
inline |
◆ cameraCallback()
void jsk_pcl_ros::IntermittentImageAnnotator::cameraCallback |
( |
const sensor_msgs::Image::ConstPtr & |
image_msg, |
|
|
const sensor_msgs::CameraInfo::ConstPtr & |
info_msg |
|
) |
| |
|
protectedvirtual |
◆ clearCallback()
bool jsk_pcl_ros::IntermittentImageAnnotator::clearCallback |
( |
std_srvs::Empty::Request & |
req, |
|
|
std_srvs::Empty::Response & |
res |
|
) |
| |
|
protectedvirtual |
◆ cloudCallback()
void jsk_pcl_ros::IntermittentImageAnnotator::cloudCallback |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
cloud_msg | ) |
|
|
protectedvirtual |
◆ onInit()
void jsk_pcl_ros::IntermittentImageAnnotator::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ 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 |
◆ rectCallback()
void jsk_pcl_ros::IntermittentImageAnnotator::rectCallback |
( |
const geometry_msgs::PolygonStamped::ConstPtr & |
rect | ) |
|
|
protectedvirtual |
◆ requestCallback()
bool jsk_pcl_ros::IntermittentImageAnnotator::requestCallback |
( |
std_srvs::Empty::Request & |
req, |
|
|
std_srvs::Empty::Response & |
res |
|
) |
| |
|
protectedvirtual |
◆ shutterCallback()
bool jsk_pcl_ros::IntermittentImageAnnotator::shutterCallback |
( |
std_srvs::Empty::Request & |
req, |
|
|
std_srvs::Empty::Response & |
res |
|
) |
| |
|
protectedvirtual |
◆ subscribe()
void jsk_pcl_ros::IntermittentImageAnnotator::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::IntermittentImageAnnotator::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ waitForNextImage()
void jsk_pcl_ros::IntermittentImageAnnotator::waitForNextImage |
( |
| ) |
|
|
protectedvirtual |
◆ clear_service_
◆ cloud_sub_
◆ fixed_frame_id_
std::string jsk_pcl_ros::IntermittentImageAnnotator::fixed_frame_id_ |
|
protected |
◆ image_pub_
◆ image_sub_
◆ keep_organized_
bool jsk_pcl_ros::IntermittentImageAnnotator::keep_organized_ |
|
protected |
◆ last_publish_time_
ros::Time jsk_pcl_ros::IntermittentImageAnnotator::last_publish_time_ |
|
protected |
◆ latest_camera_info_msg_
sensor_msgs::CameraInfo::ConstPtr jsk_pcl_ros::IntermittentImageAnnotator::latest_camera_info_msg_ |
|
protected |
◆ latest_cloud_msg_
sensor_msgs::PointCloud2::ConstPtr jsk_pcl_ros::IntermittentImageAnnotator::latest_cloud_msg_ |
|
protected |
◆ latest_image_msg_
sensor_msgs::Image::ConstPtr jsk_pcl_ros::IntermittentImageAnnotator::latest_image_msg_ |
|
protected |
◆ listener_
◆ max_image_buffer_
int jsk_pcl_ros::IntermittentImageAnnotator::max_image_buffer_ |
|
protected |
◆ mutex_
boost::mutex jsk_pcl_ros::IntermittentImageAnnotator::mutex_ |
|
protected |
◆ pub_cloud_
◆ pub_marker_
◆ pub_pose_
◆ pub_roi_
◆ rate_
double jsk_pcl_ros::IntermittentImageAnnotator::rate_ |
|
protected |
◆ rect_sub_
◆ request_service_
◆ shutter_service_
◆ snapshot_buffer_
◆ store_pointcloud_
bool jsk_pcl_ros::IntermittentImageAnnotator::store_pointcloud_ |
|
protected |
The documentation for this class was generated from the following files: