Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
jsk_interactive_marker::PointCloudCropper Class Reference

#include <pointcloud_cropper.h>

Public Member Functions

 PointCloudCropper (ros::NodeHandle &nh, ros::NodeHandle &pnh)
 
virtual ~PointCloudCropper ()
 

Protected Types

typedef PointCloudCropperConfig Config
 
typedef std::vector< interactive_markers::MenuHandler::EntryHandleEntryHandleVector
 

Protected Member Functions

virtual void changeCropper (Cropper::Ptr next_cropper)
 
virtual void changeCropperCallback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
virtual void configCallback (Config &config, uint32_t level)
 
virtual void cropAndPublish (ros::Publisher &pub)
 
virtual void initializeInteractiveMarker (Eigen::Affine3f pose_offset=Eigen::Affine3f::Identity())
 
virtual void inputCallback (const sensor_msgs::PointCloud2::ConstPtr &msg)
 
virtual void menuFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
virtual void processFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
virtual void reInitializeInteractiveMarker ()
 
virtual void updateInteractiveMarker (Eigen::Affine3f pose_offset=Eigen::Affine3f::Identity())
 
virtual void updateMenuCheckboxStatus ()
 

Protected Attributes

Cropper::Ptr cropper_
 
std::vector< Cropper::Ptrcropper_candidates_
 
EntryHandleVector cropper_entries_
 
sensor_msgs::PointCloud2::ConstPtr latest_pointcloud_
 
interactive_markers::MenuHandler menu_handler_
 
boost::mutex mutex_
 
ros::Publisher point_pub_
 
ros::Subscriber point_sub_
 
ros::Publisher point_visualization_pub_
 
std::shared_ptr< interactive_markers::InteractiveMarkerServerserver_
 
std::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
std::shared_ptr< tf::TransformListenertf_listener_
 

Detailed Description

Definition at line 124 of file pointcloud_cropper.h.

Member Typedef Documentation

typedef PointCloudCropperConfig jsk_interactive_marker::PointCloudCropper::Config
protected

Definition at line 130 of file pointcloud_cropper.h.

Definition at line 133 of file pointcloud_cropper.h.

Constructor & Destructor Documentation

jsk_interactive_marker::PointCloudCropper::PointCloudCropper ( ros::NodeHandle nh,
ros::NodeHandle pnh 
)

Definition at line 213 of file pointcloud_cropper.cpp.

jsk_interactive_marker::PointCloudCropper::~PointCloudCropper ( )
virtual

Definition at line 233 of file pointcloud_cropper.cpp.

Member Function Documentation

void jsk_interactive_marker::PointCloudCropper::changeCropper ( Cropper::Ptr  next_cropper)
protectedvirtual

Definition at line 432 of file pointcloud_cropper.cpp.

void jsk_interactive_marker::PointCloudCropper::changeCropperCallback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)
protectedvirtual

Definition at line 392 of file pointcloud_cropper.cpp.

void jsk_interactive_marker::PointCloudCropper::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

Definition at line 238 of file pointcloud_cropper.cpp.

void jsk_interactive_marker::PointCloudCropper::cropAndPublish ( ros::Publisher pub)
protectedvirtual

Definition at line 287 of file pointcloud_cropper.cpp.

void jsk_interactive_marker::PointCloudCropper::initializeInteractiveMarker ( Eigen::Affine3f  pose_offset = Eigen::Affine3f::Identity())
protectedvirtual

Definition at line 302 of file pointcloud_cropper.cpp.

void jsk_interactive_marker::PointCloudCropper::inputCallback ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
protectedvirtual

Definition at line 449 of file pointcloud_cropper.cpp.

void jsk_interactive_marker::PointCloudCropper::menuFeedback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)
protectedvirtual

Definition at line 440 of file pointcloud_cropper.cpp.

void jsk_interactive_marker::PointCloudCropper::processFeedback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)
protectedvirtual

Definition at line 249 of file pointcloud_cropper.cpp.

void jsk_interactive_marker::PointCloudCropper::reInitializeInteractiveMarker ( )
protectedvirtual

Definition at line 336 of file pointcloud_cropper.cpp.

void jsk_interactive_marker::PointCloudCropper::updateInteractiveMarker ( Eigen::Affine3f  pose_offset = Eigen::Affine3f::Identity())
protectedvirtual

Definition at line 347 of file pointcloud_cropper.cpp.

void jsk_interactive_marker::PointCloudCropper::updateMenuCheckboxStatus ( )
protectedvirtual

Definition at line 415 of file pointcloud_cropper.cpp.

Member Data Documentation

Cropper::Ptr jsk_interactive_marker::PointCloudCropper::cropper_
protected

Definition at line 159 of file pointcloud_cropper.h.

std::vector<Cropper::Ptr> jsk_interactive_marker::PointCloudCropper::cropper_candidates_
protected

Definition at line 160 of file pointcloud_cropper.h.

EntryHandleVector jsk_interactive_marker::PointCloudCropper::cropper_entries_
protected

Definition at line 161 of file pointcloud_cropper.h.

sensor_msgs::PointCloud2::ConstPtr jsk_interactive_marker::PointCloudCropper::latest_pointcloud_
protected

Definition at line 156 of file pointcloud_cropper.h.

interactive_markers::MenuHandler jsk_interactive_marker::PointCloudCropper::menu_handler_
protected

Definition at line 158 of file pointcloud_cropper.h.

boost::mutex jsk_interactive_marker::PointCloudCropper::mutex_
protected

Definition at line 150 of file pointcloud_cropper.h.

ros::Publisher jsk_interactive_marker::PointCloudCropper::point_pub_
protected

Definition at line 152 of file pointcloud_cropper.h.

ros::Subscriber jsk_interactive_marker::PointCloudCropper::point_sub_
protected

Definition at line 151 of file pointcloud_cropper.h.

ros::Publisher jsk_interactive_marker::PointCloudCropper::point_visualization_pub_
protected

Definition at line 153 of file pointcloud_cropper.h.

std::shared_ptr<interactive_markers::InteractiveMarkerServer> jsk_interactive_marker::PointCloudCropper::server_
protected

Definition at line 154 of file pointcloud_cropper.h.

std::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_interactive_marker::PointCloudCropper::srv_
protected

Definition at line 157 of file pointcloud_cropper.h.

std::shared_ptr<tf::TransformListener> jsk_interactive_marker::PointCloudCropper::tf_listener_
protected

Definition at line 162 of file pointcloud_cropper.h.


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


jsk_interactive_marker
Author(s): furuta
autogenerated on Sat Mar 20 2021 03:03:33