Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef JSK_PCL_ROS_ENVIRONMENT_PLANE_MODELING_H_
00037 #define JSK_PCL_ROS_ENVIRONMENT_PLANE_MODELING_H_
00038
00039 #include <pcl_ros/pcl_nodelet.h>
00040
00041 #include <pcl/kdtree/kdtree_flann.h>
00042 #include <message_filters/subscriber.h>
00043 #include <message_filters/time_synchronizer.h>
00044 #include <message_filters/synchronizer.h>
00045 #include <dynamic_reconfigure/server.h>
00046
00047 #include <jsk_recognition_msgs/PolygonArray.h>
00048 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
00049 #include <jsk_recognition_msgs/ClusterPointIndices.h>
00050 #include <sensor_msgs/PointCloud2.h>
00051 #include <jsk_recognition_msgs/EnvironmentLock.h>
00052 #include <jsk_recognition_msgs/PolygonOnEnvironment.h>
00053
00054 #include <jsk_recognition_utils/pcl_conversion_util.h>
00055 #include <jsk_pcl_ros/EnvironmentPlaneModelingConfig.h>
00056
00057 #include <diagnostic_updater/diagnostic_updater.h>
00058 #include <diagnostic_updater/publisher.h>
00059
00060 #include <std_srvs/Empty.h>
00061
00062 #include <jsk_topic_tools/time_accumulator.h>
00063
00064 #include "jsk_recognition_utils/pcl_util.h"
00065 #include <jsk_recognition_msgs/SimpleOccupancyGridArray.h>
00066 #include <jsk_recognition_msgs/BoundingBoxArray.h>
00067 #include <jsk_topic_tools/diagnostic_nodelet.h>
00068 #include "jsk_recognition_utils/geo_util.h"
00069 #include "jsk_pcl_ros/tf_listener_singleton.h"
00070
00071 namespace jsk_pcl_ros
00072 {
00073
00074
00075
00080 class EnvironmentPlaneModeling: public jsk_topic_tools::DiagnosticNodelet
00081 {
00082 public:
00083 typedef EnvironmentPlaneModelingConfig Config;
00084
00085 typedef message_filters::sync_policies::ExactTime<
00086 sensor_msgs::PointCloud2,
00087 sensor_msgs::PointCloud2,
00088 jsk_recognition_msgs::PolygonArray,
00089 jsk_recognition_msgs::ModelCoefficientsArray,
00090 jsk_recognition_msgs::ClusterPointIndices > SyncPolicy;
00091 EnvironmentPlaneModeling(): DiagnosticNodelet("EnvironmentPlaneModeling") {}
00092 protected:
00093 virtual void onInit();
00094
00100 virtual void subscribe() {}
00101
00107 virtual void unsubscribe() {}
00108
00113 virtual void inputCallback(
00114 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00115 const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
00116 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
00117 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
00118 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg);
00119
00120 virtual void printInputData(
00121 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00122 const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
00123 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
00124 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
00125 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg);
00126
00127
00128 virtual bool isValidFrameIds(
00129 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00130 const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
00131 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
00132 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
00133 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg);
00134
00135 virtual std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convertToConvexPolygons(
00136 const pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
00137 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
00138 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg);
00139
00140 virtual void publishConvexPolygonsBoundaries(
00141 ros::Publisher& pub,
00142 const std_msgs::Header& header,
00143 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);
00144
00149 virtual void configCallback(Config &config, uint32_t level);
00150
00155 virtual void publishConvexPolygons(
00156 ros::Publisher& pub,
00157 const std_msgs::Header& header,
00158 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);
00159
00164 virtual void publishGridMaps(
00165 ros::Publisher& pub,
00166 const std_msgs::Header& header,
00167 std::vector<GridPlane::Ptr>& grids);
00168
00173 virtual std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> magnifyConvexes(
00174 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);
00175
00180 virtual std::vector<GridPlane::Ptr> buildGridPlanes(
00181 pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
00182 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes,
00183 std::set<int>& non_plane_indices);
00184
00185 virtual std::vector<GridPlane::Ptr> morphologicalFiltering(
00186 std::vector<GridPlane::Ptr>& raw_grid_maps);
00187
00188 virtual void boundingBoxCallback(
00189 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_array);
00190
00191 virtual std::vector<GridPlane::Ptr> completeFootprintRegion(
00192 const std_msgs::Header& header,
00193 std::vector<GridPlane::Ptr>& grid_maps);
00194
00195 virtual std::vector<GridPlane::Ptr> erodeFiltering(
00196 std::vector<GridPlane::Ptr>& grid_maps);
00197
00198 virtual int lookupGroundPlaneForFootprint(
00199 const std::string& footprint_frame_id, const std_msgs::Header& header,
00200 const std::vector<GridPlane::Ptr>& grid_maps);
00201
00202 virtual int lookupGroundPlaneForFootprint(
00203 const Eigen::Affine3f& pose, const std::vector<GridPlane::Ptr>& grid_maps);
00204
00205 virtual GridPlane::Ptr completeGridMapByBoundingBox(
00206 const jsk_recognition_msgs::BoundingBox::ConstPtr& box,
00207 const std_msgs::Header& header,
00208 GridPlane::Ptr grid_map);
00209
00210 virtual void moveBaseSimpleGoalCallback(
00211 const geometry_msgs::PoseStamped::ConstPtr& msg);
00212
00213 boost::mutex mutex_;
00214 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
00215 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_cloud_;
00216 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_full_cloud_;
00217 message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_indices_;
00218 message_filters::Subscriber<jsk_recognition_msgs::PolygonArray> sub_polygons_;
00219 message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> sub_coefficients_;
00220 ros::Subscriber sub_leg_bbox_;
00221 ros::Subscriber sub_move_base_simple_goal_;
00222 ros::Publisher pub_debug_magnified_polygons_;
00223 ros::Publisher pub_debug_convex_point_cloud_;
00224 ros::Publisher pub_debug_raw_grid_map_;
00225 ros::Publisher pub_debug_noeroded_grid_map_;
00226 ros::Publisher pub_debug_plane_coords_;
00227 ros::Publisher pub_debug_magnified_plane_coords_;
00228 ros::Publisher pub_grid_map_;
00229 ros::Publisher pub_non_plane_indices_;
00230 ros::Publisher pub_snapped_move_base_simple_goal_;
00231 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00232 tf::TransformListener* tf_listener_;
00233 jsk_recognition_msgs::BoundingBox::ConstPtr latest_leg_bounding_box_;
00234 std::vector<std::string> footprint_frames_;
00235 std::vector<GridPlane::Ptr> latest_grid_maps_;
00236 std_msgs::Header latest_global_header_;
00238
00240 double magnify_distance_;
00241 double distance_threshold_;
00242 double normal_threshold_;
00243 double resolution_;
00244 int morphological_filter_size_;
00245 bool complete_footprint_region_;
00246 int erode_filter_size_;
00247 double footprint_plane_distance_threshold_;
00248 double footprint_plane_angular_threshold_;
00249 private:
00250 };
00251 }
00252
00253 #endif