#include <interactive_point_cloud.h>
|  | 
| virtual void | configCallback (Config &config, uint32_t level) | 
|  | 
| void | leftClickPoint (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
|  | 
| void | makeMarker (const sensor_msgs::PointCloud2ConstPtr cloud, const jsk_recognition_msgs::BoundingBoxArrayConstPtr box, const geometry_msgs::PoseStampedConstPtr handle, float size) | 
|  | 
| void | makeMarker (const sensor_msgs::PointCloud2ConstPtr cloud, float size) | 
|  | 
| void | makeMenu () | 
|  | 
| void | markerFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
|  | 
| void | menuPoint (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
|  | 
| void | move (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
|  | 
| void | pickup (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
|  | 
| void | publishGraspPose () | 
|  | 
| void | publishHandPose (geometry_msgs::PoseStamped box_pose) | 
|  | 
| void | setMarkerPoseCallback (const geometry_msgs::PoseStampedConstPtr &pose_stamped_msg) | 
|  | 
Definition at line 33 of file interactive_point_cloud.h.
 
◆ Config
◆ MenuHandler
◆ SyncHandlePose
◆ SyncPolicy
◆ InteractivePointCloud()
◆ ~InteractivePointCloud()
      
        
          | InteractivePointCloud::~InteractivePointCloud | ( |  | ) |  | 
      
 
 
◆ configCallback()
  
  | 
        
          | void InteractivePointCloud::configCallback | ( | Config & | config, |  
          |  |  | uint32_t | level |  
          |  | ) |  |  |  | privatevirtual | 
 
 
◆ handlePoseAndBoundingBoxCallback()
      
        
          | void InteractivePointCloud::handlePoseAndBoundingBoxCallback | ( | const jsk_recognition_msgs::Int32StampedConstPtr & | index, | 
        
          |  |  | const geometry_msgs::PoseArrayConstPtr & | pa, | 
        
          |  |  | const jsk_recognition_msgs::BoundingBoxArrayConstPtr & | box | 
        
          |  | ) |  |  | 
      
 
 
◆ handlePoseCallback()
      
        
          | void InteractivePointCloud::handlePoseCallback | ( | const geometry_msgs::PoseStampedConstPtr & | ps | ) |  | 
      
 
 
◆ hide()
      
        
          | void InteractivePointCloud::hide | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) |  | 
      
 
 
◆ leftClickPoint()
  
  | 
        
          | void InteractivePointCloud::leftClickPoint | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) |  |  | private | 
 
 
◆ makeMarker() [1/2]
  
  | 
        
          | void InteractivePointCloud::makeMarker | ( | const sensor_msgs::PointCloud2ConstPtr | cloud, |  
          |  |  | const jsk_recognition_msgs::BoundingBoxArrayConstPtr | box, |  
          |  |  | const geometry_msgs::PoseStampedConstPtr | handle, |  
          |  |  | float | size |  
          |  | ) |  |  |  | private | 
 
 
◆ makeMarker() [2/2]
  
  | 
        
          | void InteractivePointCloud::makeMarker | ( | const sensor_msgs::PointCloud2ConstPtr | cloud, |  
          |  |  | float | size |  
          |  | ) |  |  |  | private | 
 
 
◆ makeMenu()
  
  | 
        
          | void InteractivePointCloud::makeMenu | ( |  | ) |  |  | private | 
 
 
◆ markerFeedback()
  
  | 
        
          | void InteractivePointCloud::markerFeedback | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) |  |  | private | 
 
 
◆ menuPoint()
  
  | 
        
          | void InteractivePointCloud::menuPoint | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) |  |  | private | 
 
 
◆ move()
  
  | 
        
          | void InteractivePointCloud::move | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) |  |  | private | 
 
 
◆ pickup()
  
  | 
        
          | void InteractivePointCloud::pickup | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) |  |  | private | 
 
 
◆ pointCloudAndBoundingBoxCallback()
      
        
          | void InteractivePointCloud::pointCloudAndBoundingBoxCallback | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud, | 
        
          |  |  | const jsk_recognition_msgs::BoundingBoxArrayConstPtr & | box, | 
        
          |  |  | const geometry_msgs::PoseStampedConstPtr & | handle | 
        
          |  | ) |  |  | 
      
 
 
◆ pointCloudCallback()
      
        
          | void InteractivePointCloud::pointCloudCallback | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) |  | 
      
 
 
◆ publishGraspPose()
  
  | 
        
          | void InteractivePointCloud::publishGraspPose | ( |  | ) |  |  | private | 
 
 
◆ publishHandPose()
  
  | 
        
          | void InteractivePointCloud::publishHandPose | ( | geometry_msgs::PoseStamped | box_pose | ) |  |  | private | 
 
 
◆ setHandlePoseCallback()
      
        
          | void InteractivePointCloud::setHandlePoseCallback | ( | const geometry_msgs::PoseStampedConstPtr & | ps | ) |  | 
      
 
 
◆ setMarkerPoseCallback()
  
  | 
        
          | void InteractivePointCloud::setMarkerPoseCallback | ( | const geometry_msgs::PoseStampedConstPtr & | pose_stamped_msg | ) |  |  | private | 
 
 
◆ box_movement_
  
  | 
        
          | jsk_recognition_msgs::BoundingBoxMovement InteractivePointCloud::box_movement_ |  | private | 
 
 
◆ current_box_
  
  | 
        
          | jsk_recognition_msgs::BoundingBoxArray InteractivePointCloud::current_box_ |  | private | 
 
 
◆ current_croud_
  
  | 
        
          | sensor_msgs::PointCloud2 InteractivePointCloud::current_croud_ |  | private | 
 
 
◆ display_interactive_manipulator_
  
  | 
        
          | bool InteractivePointCloud::display_interactive_manipulator_ |  | private | 
 
 
◆ exist_handle_tf_
  
  | 
        
          | bool InteractivePointCloud::exist_handle_tf_ |  | private | 
 
 
◆ handle_pose_
  
  | 
        
          | geometry_msgs::PoseStamped InteractivePointCloud::handle_pose_ |  | private | 
 
 
◆ handle_tf_
◆ initial_handle_pose_
  
  | 
        
          | std::string InteractivePointCloud::initial_handle_pose_ |  | private | 
 
 
◆ input_bounding_box_
◆ input_pointcloud_
◆ marker_name_
◆ marker_pose_
  
  | 
        
          | geometry_msgs::PoseStamped InteractivePointCloud::marker_pose_ |  | private | 
 
 
◆ marker_server_
◆ menu_handler_
◆ msg_cloud_
  
  | 
        
          | sensor_msgs::PointCloud2 InteractivePointCloud::msg_cloud_ |  | private | 
 
 
◆ mutex_
◆ nh_
◆ pnh_
◆ point_size_
  
  | 
        
          | double InteractivePointCloud::point_size_ |  | private | 
 
 
◆ pub_box_movement_
◆ pub_click_point_
◆ pub_grasp_pose_
◆ pub_handle_pose_
◆ pub_handle_pose_array_
◆ pub_left_click_
◆ pub_left_click_relative_
◆ pub_marker_pose_
◆ srv_
  
  | 
        
          | std::shared_ptr<dynamic_reconfigure::Server<Config> > InteractivePointCloud::srv_ |  | private | 
 
 
◆ sub_bounding_box_
◆ sub_handle_array_
◆ sub_handle_pose_
◆ sub_initial_handle_pose_
◆ sub_marker_pose_
◆ sub_point_cloud_
◆ sub_selected_index_
◆ sync_
◆ sync_handle_
◆ tfl_
◆ topic_
◆ use_bounding_box_
  
  | 
        
          | bool InteractivePointCloud::use_bounding_box_ |  | private | 
 
 
The documentation for this class was generated from the following files: