#include <pointcloud_cropper.h>
Definition at line 124 of file pointcloud_cropper.h.
◆ Config
◆ EntryHandleVector
◆ PointCloudCropper()
◆ ~PointCloudCropper()
jsk_interactive_marker::PointCloudCropper::~PointCloudCropper |
( |
| ) |
|
|
virtual |
◆ changeCropper()
void jsk_interactive_marker::PointCloudCropper::changeCropper |
( |
Cropper::Ptr |
next_cropper | ) |
|
|
protectedvirtual |
◆ changeCropperCallback()
void jsk_interactive_marker::PointCloudCropper::changeCropperCallback |
( |
const visualization_msgs::InteractiveMarkerFeedbackConstPtr & |
feedback | ) |
|
|
protectedvirtual |
◆ configCallback()
void jsk_interactive_marker::PointCloudCropper::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ cropAndPublish()
void jsk_interactive_marker::PointCloudCropper::cropAndPublish |
( |
ros::Publisher & |
pub | ) |
|
|
protectedvirtual |
◆ initializeInteractiveMarker()
void jsk_interactive_marker::PointCloudCropper::initializeInteractiveMarker |
( |
Eigen::Affine3f |
pose_offset = Eigen::Affine3f::Identity() | ) |
|
|
protectedvirtual |
◆ inputCallback()
void jsk_interactive_marker::PointCloudCropper::inputCallback |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg | ) |
|
|
protectedvirtual |
◆ menuFeedback()
void jsk_interactive_marker::PointCloudCropper::menuFeedback |
( |
const visualization_msgs::InteractiveMarkerFeedbackConstPtr & |
feedback | ) |
|
|
protectedvirtual |
◆ processFeedback()
void jsk_interactive_marker::PointCloudCropper::processFeedback |
( |
const visualization_msgs::InteractiveMarkerFeedbackConstPtr & |
feedback | ) |
|
|
protectedvirtual |
◆ reInitializeInteractiveMarker()
void jsk_interactive_marker::PointCloudCropper::reInitializeInteractiveMarker |
( |
| ) |
|
|
protectedvirtual |
◆ updateInteractiveMarker()
void jsk_interactive_marker::PointCloudCropper::updateInteractiveMarker |
( |
Eigen::Affine3f |
pose_offset = Eigen::Affine3f::Identity() | ) |
|
|
protectedvirtual |
◆ updateMenuCheckboxStatus()
void jsk_interactive_marker::PointCloudCropper::updateMenuCheckboxStatus |
( |
| ) |
|
|
protectedvirtual |
◆ cropper_
Cropper::Ptr jsk_interactive_marker::PointCloudCropper::cropper_ |
|
protected |
◆ cropper_candidates_
◆ cropper_entries_
◆ latest_pointcloud_
sensor_msgs::PointCloud2::ConstPtr jsk_interactive_marker::PointCloudCropper::latest_pointcloud_ |
|
protected |
◆ menu_handler_
◆ mutex_
boost::mutex jsk_interactive_marker::PointCloudCropper::mutex_ |
|
protected |
◆ point_pub_
◆ point_sub_
◆ point_visualization_pub_
ros::Publisher jsk_interactive_marker::PointCloudCropper::point_visualization_pub_ |
|
protected |
◆ server_
◆ srv_
std::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_interactive_marker::PointCloudCropper::srv_ |
|
protected |
◆ tf_listener_
The documentation for this class was generated from the following files: