#include <interactive_point_cloud.h>
| Public Member Functions | |
| void | handlePoseAndBoundingBoxCallback (const jsk_recognition_msgs::Int32StampedConstPtr &index, const geometry_msgs::PoseArrayConstPtr &pa, const jsk_recognition_msgs::BoundingBoxArrayConstPtr &box) | 
| void | handlePoseCallback (const geometry_msgs::PoseStampedConstPtr &ps) | 
| void | hide (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| Clear the cloud stored in this object. | |
| InteractivePointCloud (std::string marker_name, std::string topic_name, std::string server_name) | |
| void | pointCloudAndBoundingBoxCallback (const sensor_msgs::PointCloud2ConstPtr &cloud, const jsk_recognition_msgs::BoundingBoxArrayConstPtr &box, const geometry_msgs::PoseStampedConstPtr &handle) | 
| void | pointCloudCallback (const sensor_msgs::PointCloud2ConstPtr &cloud) | 
| void | setHandlePoseCallback (const geometry_msgs::PoseStampedConstPtr &ps) | 
| ~InteractivePointCloud () | |
| Private Types | |
| typedef jsk_interactive_marker::InteractivePointCloudConfig | Config | 
| typedef interactive_markers::MenuHandler | MenuHandler | 
| typedef message_filters::sync_policies::ExactTime < jsk_recognition_msgs::Int32Stamped, geometry_msgs::PoseArray, jsk_recognition_msgs::BoundingBoxArray > | SyncHandlePose | 
| typedef message_filters::sync_policies::ExactTime < sensor_msgs::PointCloud2, jsk_recognition_msgs::BoundingBoxArray, geometry_msgs::PoseStamped > | SyncPolicy | 
| Private Member Functions | |
| virtual void | configCallback (Config &config, uint32_t level) | 
| void | leftClickPoint (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) | 
| void | makeMarker (const sensor_msgs::PointCloud2ConstPtr cloud, float size) | 
| void | makeMarker (const sensor_msgs::PointCloud2ConstPtr cloud, const jsk_recognition_msgs::BoundingBoxArrayConstPtr box, const geometry_msgs::PoseStampedConstPtr handle, 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) | 
| Private Attributes | |
| jsk_recognition_msgs::BoundingBoxMovement | box_movement_ | 
| jsk_recognition_msgs::BoundingBoxArray | current_box_ | 
| sensor_msgs::PointCloud2 | current_croud_ | 
| bool | display_interactive_manipulator_ | 
| bool | exist_handle_tf_ | 
| geometry_msgs::PoseStamped | handle_pose_ | 
| tf::Transform | handle_tf_ | 
| std::string | initial_handle_pose_ | 
| std::string | input_bounding_box_ | 
| std::string | input_pointcloud_ | 
| std::string | marker_name_ | 
| geometry_msgs::PoseStamped | marker_pose_ | 
| jsk_interactive_marker::ParentAndChildInteractiveMarkerServer | marker_server_ | 
| interactive_markers::MenuHandler | menu_handler_ | 
| sensor_msgs::PointCloud2 | msg_cloud_ | 
| boost::mutex | mutex_ | 
| ros::NodeHandle | nh_ | 
| ros::NodeHandle | pnh_ | 
| double | point_size_ | 
| ros::Publisher | pub_box_movement_ | 
| ros::Publisher | pub_click_point_ | 
| ros::Publisher | pub_grasp_pose_ | 
| ros::Publisher | pub_handle_pose_ | 
| ros::Publisher | pub_handle_pose_array_ | 
| ros::Publisher | pub_left_click_ | 
| ros::Publisher | pub_left_click_relative_ | 
| ros::Publisher | pub_marker_pose_ | 
| std::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ | 
| message_filters::Subscriber < jsk_recognition_msgs::BoundingBoxArray > | sub_bounding_box_ | 
| message_filters::Subscriber < geometry_msgs::PoseArray > | sub_handle_array_ | 
| ros::Subscriber | sub_handle_pose_ | 
| message_filters::Subscriber < geometry_msgs::PoseStamped > | sub_initial_handle_pose_ | 
| ros::Subscriber | sub_marker_pose_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_point_cloud_ | 
| message_filters::Subscriber < jsk_recognition_msgs::Int32Stamped > | sub_selected_index_ | 
| std::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ | 
| std::shared_ptr < message_filters::Synchronizer < SyncHandlePose > > | sync_handle_ | 
| tf::TransformListener | tfl_ | 
| std::string | topic_ | 
| bool | use_bounding_box_ | 
Definition at line 33 of file interactive_point_cloud.h.
| typedef jsk_interactive_marker::InteractivePointCloudConfig InteractivePointCloud::Config  [private] | 
Definition at line 53 of file interactive_point_cloud.h.
| typedef interactive_markers::MenuHandler InteractivePointCloud::MenuHandler  [private] | 
Definition at line 58 of file interactive_point_cloud.h.
| typedef message_filters::sync_policies::ExactTime<jsk_recognition_msgs::Int32Stamped, geometry_msgs::PoseArray, jsk_recognition_msgs::BoundingBoxArray> InteractivePointCloud::SyncHandlePose  [private] | 
Definition at line 62 of file interactive_point_cloud.h.
| typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, jsk_recognition_msgs::BoundingBoxArray, geometry_msgs::PoseStamped> InteractivePointCloud::SyncPolicy  [private] | 
Definition at line 59 of file interactive_point_cloud.h.
| InteractivePointCloud::InteractivePointCloud | ( | std::string | marker_name, | 
| std::string | topic_name, | ||
| std::string | server_name | ||
| ) | 
Definition at line 20 of file interactive_point_cloud.cpp.
Definition at line 71 of file interactive_point_cloud.cpp.
| void InteractivePointCloud::configCallback | ( | Config & | config, | 
| uint32_t | level | ||
| ) |  [private, virtual] | 
Definition at line 73 of file interactive_point_cloud.cpp.
| void InteractivePointCloud::handlePoseAndBoundingBoxCallback | ( | const jsk_recognition_msgs::Int32StampedConstPtr & | index, | 
| const geometry_msgs::PoseArrayConstPtr & | pa, | ||
| const jsk_recognition_msgs::BoundingBoxArrayConstPtr & | box | ||
| ) | 
| void InteractivePointCloud::handlePoseCallback | ( | const geometry_msgs::PoseStampedConstPtr & | ps | ) | 
| void InteractivePointCloud::hide | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | 
Clear the cloud stored in this object.
Definition at line 186 of file interactive_point_cloud.cpp.
| void InteractivePointCloud::leftClickPoint | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) |  [private] | 
Definition at line 161 of file interactive_point_cloud.cpp.
| void InteractivePointCloud::makeMarker | ( | const sensor_msgs::PointCloud2ConstPtr | cloud, | 
| float | size | ||
| ) |  [private] | 
Definition at line 229 of file interactive_point_cloud.cpp.
| void InteractivePointCloud::makeMarker | ( | const sensor_msgs::PointCloud2ConstPtr | cloud, | 
| const jsk_recognition_msgs::BoundingBoxArrayConstPtr | box, | ||
| const geometry_msgs::PoseStampedConstPtr | handle, | ||
| float | size | ||
| ) |  [private] | 
Definition at line 232 of file interactive_point_cloud.cpp.
| void InteractivePointCloud::makeMenu | ( | ) |  [private] | 
Definition at line 147 of file interactive_point_cloud.cpp.
| void InteractivePointCloud::markerFeedback | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) |  [private] | 
Definition at line 193 of file interactive_point_cloud.cpp.
| void InteractivePointCloud::menuPoint | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) |  [private] | 
| void InteractivePointCloud::move | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) |  [private] | 
Definition at line 155 of file interactive_point_cloud.cpp.
| void InteractivePointCloud::pickup | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) |  [private] | 
| void InteractivePointCloud::pointCloudAndBoundingBoxCallback | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud, | 
| const jsk_recognition_msgs::BoundingBoxArrayConstPtr & | box, | ||
| const geometry_msgs::PoseStampedConstPtr & | handle | ||
| ) | 
Definition at line 103 of file interactive_point_cloud.cpp.
| void InteractivePointCloud::pointCloudCallback | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) | 
Definition at line 99 of file interactive_point_cloud.cpp.
| void InteractivePointCloud::publishGraspPose | ( | ) |  [private] | 
Definition at line 201 of file interactive_point_cloud.cpp.
| void InteractivePointCloud::publishHandPose | ( | geometry_msgs::PoseStamped | box_pose | ) |  [private] | 
Definition at line 205 of file interactive_point_cloud.cpp.
| void InteractivePointCloud::setHandlePoseCallback | ( | const geometry_msgs::PoseStampedConstPtr & | ps | ) | 
Definition at line 109 of file interactive_point_cloud.cpp.
| void InteractivePointCloud::setMarkerPoseCallback | ( | const geometry_msgs::PoseStampedConstPtr & | pose_stamped_msg | ) |  [private] | 
Definition at line 141 of file interactive_point_cloud.cpp.
| jsk_recognition_msgs::BoundingBoxMovement InteractivePointCloud::box_movement_  [private] | 
Definition at line 118 of file interactive_point_cloud.h.
| jsk_recognition_msgs::BoundingBoxArray InteractivePointCloud::current_box_  [private] | 
Definition at line 112 of file interactive_point_cloud.h.
| sensor_msgs::PointCloud2 InteractivePointCloud::current_croud_  [private] | 
Definition at line 111 of file interactive_point_cloud.h.
| bool InteractivePointCloud::display_interactive_manipulator_  [private] | 
Definition at line 116 of file interactive_point_cloud.h.
| bool InteractivePointCloud::exist_handle_tf_  [private] | 
Definition at line 115 of file interactive_point_cloud.h.
| geometry_msgs::PoseStamped InteractivePointCloud::handle_pose_  [private] | 
Definition at line 113 of file interactive_point_cloud.h.
Definition at line 114 of file interactive_point_cloud.h.
Definition at line 109 of file interactive_point_cloud.h.
Definition at line 109 of file interactive_point_cloud.h.
Definition at line 109 of file interactive_point_cloud.h.
Definition at line 84 of file interactive_point_cloud.h.
| geometry_msgs::PoseStamped InteractivePointCloud::marker_pose_  [private] | 
Definition at line 108 of file interactive_point_cloud.h.
| jsk_interactive_marker::ParentAndChildInteractiveMarkerServer InteractivePointCloud::marker_server_  [private] | 
Definition at line 101 of file interactive_point_cloud.h.
Definition at line 102 of file interactive_point_cloud.h.
| sensor_msgs::PointCloud2 InteractivePointCloud::msg_cloud_  [private] | 
Definition at line 104 of file interactive_point_cloud.h.
| boost::mutex InteractivePointCloud::mutex_  [private] | 
Definition at line 55 of file interactive_point_cloud.h.
| ros::NodeHandle InteractivePointCloud::nh_  [private] | 
Definition at line 85 of file interactive_point_cloud.h.
| ros::NodeHandle InteractivePointCloud::pnh_  [private] | 
Definition at line 86 of file interactive_point_cloud.h.
| double InteractivePointCloud::point_size_  [private] | 
Definition at line 105 of file interactive_point_cloud.h.
Definition at line 87 of file interactive_point_cloud.h.
Definition at line 87 of file interactive_point_cloud.h.
Definition at line 87 of file interactive_point_cloud.h.
Definition at line 87 of file interactive_point_cloud.h.
Definition at line 87 of file interactive_point_cloud.h.
Definition at line 87 of file interactive_point_cloud.h.
Definition at line 87 of file interactive_point_cloud.h.
Definition at line 87 of file interactive_point_cloud.h.
| std::shared_ptr<dynamic_reconfigure::Server<Config> > InteractivePointCloud::srv_  [private] | 
Definition at line 54 of file interactive_point_cloud.h.
| message_filters::Subscriber<jsk_recognition_msgs::BoundingBoxArray> InteractivePointCloud::sub_bounding_box_  [private] | 
Definition at line 92 of file interactive_point_cloud.h.
| message_filters::Subscriber<geometry_msgs::PoseArray> InteractivePointCloud::sub_handle_array_  [private] | 
Definition at line 96 of file interactive_point_cloud.h.
Definition at line 88 of file interactive_point_cloud.h.
| message_filters::Subscriber<geometry_msgs::PoseStamped> InteractivePointCloud::sub_initial_handle_pose_  [private] | 
Definition at line 93 of file interactive_point_cloud.h.
Definition at line 89 of file interactive_point_cloud.h.
| message_filters::Subscriber<sensor_msgs::PointCloud2> InteractivePointCloud::sub_point_cloud_  [private] | 
Definition at line 91 of file interactive_point_cloud.h.
| message_filters::Subscriber<jsk_recognition_msgs::Int32Stamped> InteractivePointCloud::sub_selected_index_  [private] | 
Definition at line 95 of file interactive_point_cloud.h.
| std::shared_ptr<message_filters::Synchronizer<SyncPolicy> > InteractivePointCloud::sync_  [private] | 
Definition at line 98 of file interactive_point_cloud.h.
| std::shared_ptr<message_filters::Synchronizer<SyncHandlePose> > InteractivePointCloud::sync_handle_  [private] | 
Definition at line 99 of file interactive_point_cloud.h.
Definition at line 97 of file interactive_point_cloud.h.
| std::string InteractivePointCloud::topic_  [private] | 
Definition at line 84 of file interactive_point_cloud.h.
| bool InteractivePointCloud::use_bounding_box_  [private] | 
Definition at line 106 of file interactive_point_cloud.h.