interactive_point_cloud.h
Go to the documentation of this file.
00001 #ifndef INTERACTIVE_POINT_CLOUD
00002 #define INTERACTIVE_POINT_CLOUD
00003 
00004 #include <ros/ros.h>
00005 
00006 #include <interactive_markers/interactive_marker_server.h>
00007 #include <interactive_markers/menu_handler.h>
00008 #include <sensor_msgs/PointCloud2.h>
00009 #include <jsk_recognition_msgs/BoundingBoxArray.h>
00010 #include <jsk_recognition_msgs/BoundingBoxMovement.h>
00011 #include <jsk_recognition_msgs/Int32Stamped.h>
00012 #include <geometry_msgs/PoseArray.h>
00013 
00014 #include <actionlib/client/simple_action_client.h>
00015 //#include <point_cloud_server/StoreCloudAction.h>
00016 #include <pcl/search/kdtree.h>
00017 #include <tf/tf.h>
00018 #include <tf/transform_listener.h>
00019 
00020 //#include <object_manipulator/tools/mechanism_interface.h>
00021 #include "jsk_interactive_marker/InteractivePointCloudConfig.h"
00022 #include <dynamic_reconfigure/server.h>
00023 
00024 #include <message_filters/subscriber.h>
00025 #include <message_filters/time_synchronizer.h>
00026 #include <message_filters/synchronizer.h>
00027 #include <message_filters/sync_policies/approximate_time.h>
00028 
00029 typedef pcl::PointXYZRGB PointT;
00030 
00031 
00032 class InteractivePointCloud
00033 {
00034 public:
00035 
00036   InteractivePointCloud(
00037                 std::string marker_name,
00038                 std::string topic_name, std::string server_name);
00039 
00040   ~InteractivePointCloud();
00041 
00043   void hide(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
00044   void handlePoseCallback(const geometry_msgs::PoseStampedConstPtr &ps);
00045   void pointCloudAndBoundingBoxCallback(const sensor_msgs::PointCloud2ConstPtr &cloud, const jsk_recognition_msgs::BoundingBoxArrayConstPtr &box, const geometry_msgs::PoseStampedConstPtr &handle);
00046   void pointCloudCallback(const sensor_msgs::PointCloud2ConstPtr &cloud);
00047   //  void handlePoseAndBoundingBoxCallback(const geometry_msgs::PoseStampedConstPtr &ps, const jsk_recognition_msgs::BoundingBoxArrayConstPtr &box);
00048   void setHandlePoseCallback(const geometry_msgs::PoseStampedConstPtr &ps);
00049   void handlePoseAndBoundingBoxCallback(const jsk_recognition_msgs::Int32StampedConstPtr &index, const geometry_msgs::PoseArrayConstPtr &pa, const jsk_recognition_msgs::BoundingBoxArrayConstPtr &box);
00050 private:
00051 
00052   typedef jsk_interactive_marker::InteractivePointCloudConfig Config;
00053   boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00054   boost::mutex mutex_;
00055   virtual void configCallback (Config &config, uint32_t level);
00056 
00057   typedef interactive_markers::MenuHandler MenuHandler;
00058   typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, jsk_recognition_msgs::BoundingBoxArray, geometry_msgs::PoseStamped> SyncPolicy;
00059   //typedef message_filters::sync_policies::ExactTime<geometry_msgs::PoseStamped, jsk_recognition_msgs::BoundingBoxArray> SyncHandlePose;
00060 
00061   typedef message_filters::sync_policies::ExactTime<jsk_recognition_msgs::Int32Stamped, geometry_msgs::PoseArray, jsk_recognition_msgs::BoundingBoxArray> SyncHandlePose;
00062   
00063 
00064   void makeMenu();
00065 
00066   void pickup( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00067 
00068   void makeMarker(const sensor_msgs::PointCloud2ConstPtr cloud, float size);
00069   void makeMarker(const sensor_msgs::PointCloud2ConstPtr cloud, const jsk_recognition_msgs::BoundingBoxArrayConstPtr box, const geometry_msgs::PoseStampedConstPtr handle, float size);
00070 
00071   void menuPoint( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00072   void move( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00073 
00074   void leftClickPoint( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00075 
00076   void markerFeedback( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
00077 
00078   void publishGraspPose();
00079   void publishHandPose( geometry_msgs::PoseStamped box_pose);
00080   
00081   void setMarkerPoseCallback( const geometry_msgs::PoseStampedConstPtr &pose_stamped_msg);
00082 
00083   std::string marker_name_, topic_;
00084   ros::NodeHandle nh_;
00085   ros::NodeHandle pnh_;
00086   ros::Publisher pub_marker_pose_, pub_click_point_, pub_left_click_, pub_left_click_relative_, pub_handle_pose_, pub_handle_pose_array_, pub_box_movement_, pub_grasp_pose_;
00087   ros::Subscriber sub_handle_pose_;
00088   ros::Subscriber sub_marker_pose_;
00089   //ros::Subscriber sub_point_cloud_, sub_bounding_box_;
00090   message_filters::Subscriber<sensor_msgs::PointCloud2> sub_point_cloud_;
00091   message_filters::Subscriber<jsk_recognition_msgs::BoundingBoxArray> sub_bounding_box_;
00092   message_filters::Subscriber<geometry_msgs::PoseStamped> sub_initial_handle_pose_;
00093   //message_filters::Subscriber<geometry_msgs::PoseStamped> sub_handle_pose_;
00094   message_filters::Subscriber<jsk_recognition_msgs::Int32Stamped> sub_selected_index_;
00095   message_filters::Subscriber<geometry_msgs::PoseArray> sub_handle_array_;
00096   tf::TransformListener tfl_;
00097   boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00098   boost::shared_ptr<message_filters::Synchronizer<SyncHandlePose> > sync_handle_;
00099   
00100   interactive_markers::InteractiveMarkerServer marker_server_;
00101   interactive_markers::MenuHandler menu_handler_;
00102 
00103   sensor_msgs::PointCloud2 msg_cloud_;
00104   double point_size_;
00105   bool use_bounding_box_;
00106 
00107   geometry_msgs::PoseStamped marker_pose_;
00108   std::string input_pointcloud_, input_bounding_box_, initial_handle_pose_;
00109 
00110   sensor_msgs::PointCloud2 current_croud_;
00111   jsk_recognition_msgs::BoundingBoxArray current_box_;
00112   geometry_msgs::PoseStamped handle_pose_;
00113   tf::Transform handle_tf_;
00114   bool exist_handle_tf_;
00115   bool display_interactive_manipulator_;
00116 
00117   jsk_recognition_msgs::BoundingBoxMovement box_movement_;
00118 };
00119 
00120 #endif


jsk_interactive_marker
Author(s): furuta
autogenerated on Sun Sep 13 2015 22:29:27