36 #ifndef JSK_PCL_ROS_ENVIRONMENT_PLANE_MODELING_H_ 37 #define JSK_PCL_ROS_ENVIRONMENT_PLANE_MODELING_H_ 41 #include <pcl/kdtree/kdtree_flann.h> 45 #include <dynamic_reconfigure/server.h> 47 #include <jsk_recognition_msgs/PolygonArray.h> 48 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 49 #include <jsk_recognition_msgs/ClusterPointIndices.h> 50 #include <sensor_msgs/PointCloud2.h> 51 #include <jsk_recognition_msgs/EnvironmentLock.h> 52 #include <jsk_recognition_msgs/PolygonOnEnvironment.h> 55 #include <jsk_pcl_ros/EnvironmentPlaneModelingConfig.h> 60 #include <std_srvs/Empty.h> 65 #include <jsk_recognition_msgs/SimpleOccupancyGridArray.h> 66 #include <jsk_recognition_msgs/BoundingBoxArray.h> 83 typedef EnvironmentPlaneModelingConfig
Config;
86 sensor_msgs::PointCloud2,
87 sensor_msgs::PointCloud2,
88 jsk_recognition_msgs::PolygonArray,
89 jsk_recognition_msgs::ModelCoefficientsArray,
114 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
115 const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
116 const jsk_recognition_msgs::PolygonArray::ConstPtr&
polygon_msg,
117 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
118 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg);
121 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
122 const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
123 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
124 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
125 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg);
129 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
130 const sensor_msgs::PointCloud2::ConstPtr& full_cloud_msg,
131 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
132 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
133 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg);
136 const pcl::PointCloud<pcl::PointNormal>::Ptr&
cloud,
137 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
138 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg);
142 const std_msgs::Header&
header,
143 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);
157 const std_msgs::Header& header,
158 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);
166 const std_msgs::Header& header,
167 std::vector<GridPlane::Ptr>& grids);
173 virtual std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>
magnifyConvexes(
174 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);
181 pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
182 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes,
183 std::set<int>& non_plane_indices);
186 std::vector<GridPlane::Ptr>& raw_grid_maps);
189 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_array);
192 const std_msgs::Header& header,
193 std::vector<GridPlane::Ptr>& grid_maps);
196 std::vector<GridPlane::Ptr>& grid_maps);
199 const std::string& footprint_frame_id,
const std_msgs::Header& header,
200 const std::vector<GridPlane::Ptr>& grid_maps);
203 const Eigen::Affine3f&
pose,
const std::vector<GridPlane::Ptr>& grid_maps);
206 const jsk_recognition_msgs::BoundingBox::ConstPtr&
box,
207 const std_msgs::Header& header,
211 const geometry_msgs::PoseStamped::ConstPtr&
msg);
virtual std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > magnifyConvexes(std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
Magnify jsk_recognition_utils::ConvexPolygons according to maginify_distance_ parameter.
virtual void configCallback(Config &config, uint32_t level)
Callback method of dynamic reconfigure.
virtual GridPlane::Ptr completeGridMapByBoundingBox(const jsk_recognition_msgs::BoundingBox::ConstPtr &box, const std_msgs::Header &header, GridPlane::Ptr grid_map)
ros::Subscriber sub_leg_bbox_
virtual std::vector< GridPlane::Ptr > completeFootprintRegion(const std_msgs::Header &header, std::vector< GridPlane::Ptr > &grid_maps)
virtual std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > convertToConvexPolygons(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
ros::Publisher pub_debug_raw_grid_map_
ros::Publisher pub_grid_map_
ros::Publisher pub_debug_plane_coords_
virtual std::vector< GridPlane::Ptr > erodeFiltering(std::vector< GridPlane::Ptr > &grid_maps)
bool complete_footprint_region_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
ros::Publisher pub_debug_magnified_plane_coords_
virtual std::vector< GridPlane::Ptr > morphologicalFiltering(std::vector< GridPlane::Ptr > &raw_grid_maps)
virtual void unsubscribe()
unsubscription callback function of jsk_topic_tools::DiagnosticNodelet. This method is empty method b...
virtual void boundingBoxCallback(const jsk_recognition_msgs::BoundingBox::ConstPtr &box_array)
virtual void publishConvexPolygonsBoundaries(ros::Publisher &pub, const std_msgs::Header &header, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
ros::Publisher pub_debug_magnified_polygons_
virtual void inputCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &full_cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
main callback function
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_full_cloud_
Nodelet implementation of jsk_pcl/EnvironmentPlaneModeling.
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
virtual void moveBaseSimpleGoalCallback(const geometry_msgs::PoseStamped::ConstPtr &msg)
ros::Publisher pub_debug_noeroded_grid_map_
double footprint_plane_distance_threshold_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
std_msgs::Header latest_global_header_
jsk_recognition_msgs::PolygonArray::ConstPtr polygon_msg
std::vector< std::string > footprint_frames_
EnvironmentPlaneModelingConfig Config
tf::TransformListener * tf_listener_
virtual std::vector< GridPlane::Ptr > buildGridPlanes(pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > convexes, std::set< int > &non_plane_indices)
make GridPlane from jsk_recognition_utils::ConvexPolygon and PointCloud
ros::Subscriber sub_move_base_simple_goal_
double distance_threshold_
virtual void printInputData(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &full_cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
virtual bool isValidFrameIds(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &full_cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
ros::Publisher pub_non_plane_indices_
virtual void publishConvexPolygons(ros::Publisher &pub, const std_msgs::Header &header, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
Publish array of jsk_recognition_utils::ConvexPolygon::Ptr by using specified publisher.
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
double footprint_plane_angular_threshold_
virtual void subscribe()
subscription callback function of jsk_topic_tools::DiagnosticNodelet. This method is empty method bec...
boost::mutex mutex
global mutex.
ros::Publisher pub_debug_convex_point_cloud_
ros::Publisher pub_snapped_move_base_simple_goal_
virtual int lookupGroundPlaneForFootprint(const std::string &footprint_frame_id, const std_msgs::Header &header, const std::vector< GridPlane::Ptr > &grid_maps)
std::vector< GridPlane::Ptr > latest_grid_maps_
EnvironmentPlaneModeling()
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray, jsk_recognition_msgs::ClusterPointIndices > SyncPolicy
int morphological_filter_size_
virtual void publishGridMaps(ros::Publisher &pub, const std_msgs::Header &header, std::vector< GridPlane::Ptr > &grids)
Publish array of GridPlane::Ptr by using specified publisher.
jsk_recognition_msgs::BoundingBox::ConstPtr latest_leg_bounding_box_