Go to the documentation of this file.    1 #ifndef INTERACTIVE_POINT_CLOUD 
    2 #define INTERACTIVE_POINT_CLOUD 
    8 #include <sensor_msgs/PointCloud2.h> 
    9 #include <jsk_recognition_msgs/BoundingBoxArray.h> 
   10 #include <jsk_recognition_msgs/BoundingBoxMovement.h> 
   11 #include <jsk_recognition_msgs/Int32Stamped.h> 
   12 #include <geometry_msgs/PoseArray.h> 
   16 #include <pcl/search/kdtree.h> 
   21 #include "jsk_interactive_marker/InteractivePointCloudConfig.h" 
   23 #include <dynamic_reconfigure/server.h> 
   38                 std::string marker_name,
 
   39                 std::string topic_name, std::string server_name);
 
   44   void hide(
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
 
   46   void pointCloudAndBoundingBoxCallback(
const sensor_msgs::PointCloud2ConstPtr &cloud, 
const jsk_recognition_msgs::BoundingBoxArrayConstPtr &box, 
const geometry_msgs::PoseStampedConstPtr &handle);
 
   50   void handlePoseAndBoundingBoxCallback(
const jsk_recognition_msgs::Int32StampedConstPtr &
index, 
const geometry_msgs::PoseArrayConstPtr &pa, 
const jsk_recognition_msgs::BoundingBoxArrayConstPtr &box);
 
   53   typedef jsk_interactive_marker::InteractivePointCloudConfig 
Config;
 
   54   std::shared_ptr <dynamic_reconfigure::Server<Config> > 
srv_;
 
   67   void pickup( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
   69   void makeMarker(
const sensor_msgs::PointCloud2ConstPtr cloud, 
float size);
 
   70   void makeMarker(
const sensor_msgs::PointCloud2ConstPtr cloud, 
const jsk_recognition_msgs::BoundingBoxArrayConstPtr box, 
const geometry_msgs::PoseStampedConstPtr handle, 
float size);
 
   72   void menuPoint( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
   73   void move( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
   75   void leftClickPoint( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
 
   77   void markerFeedback( 
const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
 
   98   std::shared_ptr<message_filters::Synchronizer<SyncPolicy> >
sync_;
 
   99   std::shared_ptr<message_filters::Synchronizer<SyncHandlePose> > 
sync_handle_;
 
 
interactive_markers::MenuHandler MenuHandler
void setHandlePoseCallback(const geometry_msgs::PoseStampedConstPtr &ps)
ros::Publisher pub_handle_pose_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_point_cloud_
ros::Publisher pub_marker_pose_
jsk_interactive_marker::ParentAndChildInteractiveMarkerServer marker_server_
std::string input_pointcloud_
message_filters::Subscriber< geometry_msgs::PoseArray > sub_handle_array_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::BoundingBoxArray, geometry_msgs::PoseStamped > SyncPolicy
void setMarkerPoseCallback(const geometry_msgs::PoseStampedConstPtr &pose_stamped_msg)
jsk_recognition_msgs::BoundingBoxMovement box_movement_
jsk_interactive_marker::InteractivePointCloudConfig Config
InteractivePointCloud(std::string marker_name, std::string topic_name, std::string server_name)
void menuPoint(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void hide(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
Clear the cloud stored in this object.
ros::Subscriber sub_handle_pose_
ros::Publisher pub_handle_pose_array_
sensor_msgs::PointCloud2 msg_cloud_
std::string initial_handle_pose_
geometry_msgs::PoseStamped handle_pose_
bool display_interactive_manipulator_
ros::Subscriber sub_marker_pose_
void markerFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
std::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
ros::Publisher pub_left_click_
void handlePoseCallback(const geometry_msgs::PoseStampedConstPtr &ps)
void pointCloudAndBoundingBoxCallback(const sensor_msgs::PointCloud2ConstPtr &cloud, const jsk_recognition_msgs::BoundingBoxArrayConstPtr &box, const geometry_msgs::PoseStampedConstPtr &handle)
void makeMarker(const sensor_msgs::PointCloud2ConstPtr cloud, float size)
geometry_msgs::PoseStamped marker_pose_
void pickup(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
std::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
void leftClickPoint(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
ros::Publisher pub_click_point_
void move(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
ros::Publisher pub_left_click_relative_
std::shared_ptr< message_filters::Synchronizer< SyncHandlePose > > sync_handle_
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_initial_handle_pose_
message_filters::Subscriber< jsk_recognition_msgs::Int32Stamped > sub_selected_index_
ros::Publisher pub_box_movement_
interactive_markers::MenuHandler menu_handler_
std::string input_bounding_box_
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::Int32Stamped, geometry_msgs::PoseArray, jsk_recognition_msgs::BoundingBoxArray > SyncHandlePose
void pointCloudCallback(const sensor_msgs::PointCloud2ConstPtr &cloud)
tf::TransformListener tfl_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArray > sub_bounding_box_
sensor_msgs::PointCloud2 current_croud_
ros::Publisher pub_grasp_pose_
void publishHandPose(geometry_msgs::PoseStamped box_pose)
virtual void configCallback(Config &config, uint32_t level)
jsk_recognition_msgs::BoundingBoxArray current_box_
void handlePoseAndBoundingBoxCallback(const jsk_recognition_msgs::Int32StampedConstPtr &index, const geometry_msgs::PoseArrayConstPtr &pa, const jsk_recognition_msgs::BoundingBoxArrayConstPtr &box)