37 #ifndef JSK_PCL_ROS_EDGE_BASED_CUBE_FINDER_H_ 38 #define JSK_PCL_ROS_EDGE_BASED_CUBE_FINDER_H_ 45 #include <sensor_msgs/PointCloud2.h> 46 #include <jsk_recognition_msgs/ParallelEdge.h> 47 #include <jsk_recognition_msgs/PolygonArray.h> 48 #include <jsk_recognition_msgs/BoundingBoxArray.h> 49 #include <jsk_recognition_msgs/ParallelEdgeArray.h> 59 #include <boost/tuple/tuple.hpp> 60 #include <jsk_pcl_ros/EdgebasedCubeFinderConfig.h> 61 #include <dynamic_reconfigure/server.h> 67 typedef boost::tuple<pcl::PointIndices::Ptr, pcl::PointIndices::Ptr>
69 typedef boost::tuple<pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr>
72 typedef boost::tuple<pcl::PointIndices::Ptr, pcl::PointIndices::Ptr, pcl::PointIndices::Ptr>
74 typedef boost::tuple<pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr>
76 typedef boost::tuple<IndicesTriple, CoefficientsTriple>
89 const double outlier_threshold);
93 virtual void estimate(
const pcl::PointCloud<pcl::PointXYZRGB>&
cloud) = 0;
96 const pcl::PointCloud<pcl::PointXYZRGB>& cloud,
107 virtual void computeCentroid(
const pcl::PointCloud<pcl::PointXYZRGB>::Ptr& cloud,
108 const pcl::PointIndices::Ptr& indices,
111 const pcl::PointCloud<pcl::PointXYZRGB>& cloud,
112 const pcl::PointIndices::Ptr indices,
134 const double outlier_threshold);
135 virtual void estimate(
const pcl::PointCloud<pcl::PointXYZRGB>& cloud)
149 const double outlier_threshold);
150 virtual void estimate(
const pcl::PointCloud<pcl::PointXYZRGB>& cloud);
161 sensor_msgs::PointCloud2,
164 typedef jsk_pcl_ros::EdgebasedCubeFinderConfig
Config;
179 virtual void onInit();
182 const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
183 const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr& input_edges);
184 virtual void estimate2(
185 const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
186 const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr& input_edges);
193 virtual std::vector<IndicesPair> combinateIndices(
194 const std::vector<pcl::PointIndices::Ptr>& indices);
196 virtual std::vector<CoefficientsPair> combinateCoefficients(
197 const std::vector<pcl::ModelCoefficients::Ptr>& coefficients);
199 virtual bool isPerpendicularVector(
200 const Eigen::Vector3f& a,
201 const Eigen::Vector3f& b);
203 virtual std::vector<IndicesCoefficientsTriple>
204 tripleIndicesAndCoefficients(
205 const std::vector<pcl::PointIndices::Ptr>& indices,
206 const std::vector<pcl::ModelCoefficients::Ptr>& coefficients);
214 virtual std::vector<IndicesCoefficientsTriple>
215 filterPerpendicularEdgeTriples(
216 const std::vector<IndicesCoefficientsTriple>& triples);
222 const pcl::PointCloud<PointT>::Ptr cloud,
225 virtual int countInliers(
226 const pcl::PointCloud<PointT>::Ptr cloud,
228 virtual void filterBasedOnConvex(
229 const pcl::PointCloud<PointT>::Ptr cloud,
230 const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes,
231 std::vector<int>& output_indices);
232 virtual void filterPairsBasedOnParallelEdgeDistances(
233 const std::vector<IndicesPair>& pairs,
234 const std::vector<CoefficientsPair>& coefficients_pair,
235 std::vector<IndicesPair>& filtered_indices_pairs,
236 std::vector<CoefficientsPair>& filtered_coefficients_pairs);
239 const pcl::PointCloud<PointT>::Ptr cloud,
241 pcl::PointCloud<EdgebasedCubeFinder::PointT>::Ptr points_on_edge);
243 virtual pcl::PointCloud<PointT>::Ptr extractPointCloud(
244 const pcl::PointCloud<PointT>::Ptr cloud,
245 const pcl::PointIndices::Ptr indices);
249 const pcl::PointCloud<PointT>::Ptr cloud);
251 virtual void estimateParallelPlane(
253 const pcl::PointCloud<PointT>::Ptr filtered_cloud,
254 pcl::PointIndices::Ptr output_inliers,
255 pcl::ModelCoefficients::Ptr output_coefficients);
257 virtual void estimatePerpendicularPlane(
260 const pcl::PointCloud<PointT>::Ptr filtered_cloud,
261 pcl::PointIndices::Ptr output_inliers,
262 pcl::ModelCoefficients::Ptr output_coefficients);
265 virtual pcl::PointIndices::Ptr
266 preparePointCloudForRANSAC(
269 const pcl::PointCloud<PointT>::Ptr cloud);
272 estimateConvexPolygon(
273 const pcl::PointCloud<PointT>::Ptr cloud,
274 const pcl::PointIndices::Ptr indices,
275 pcl::ModelCoefficients::Ptr coefficients,
276 pcl::PointIndices::Ptr inliers);
278 virtual void configCallback (Config &config, uint32_t level);
281 virtual void unsubscribe();
virtual void getLinePoints(const jsk_recognition_utils::Line &line, const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const pcl::PointIndices::Ptr indices, jsk_recognition_utils::Vertices &output)
virtual void estimate(const pcl::PointCloud< pcl::PointXYZRGB > &cloud)=0
boost::shared_ptr< PlanarCubeHypothesis > Ptr
double parallel_edge_distance_min_threshold_
virtual jsk_recognition_utils::PointPair computeAxisEndPoints(const jsk_recognition_utils::Line &axis, const jsk_recognition_utils::PointPair &a_candidates, const jsk_recognition_utils::PointPair &b_candidates)
virtual double getValue()
boost::tuple< pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr > CoefficientsPair
virtual jsk_recognition_utils::ConvexPolygon::Ptr buildConvexPolygon(const jsk_recognition_utils::PointPair &a_edge_pair, const jsk_recognition_utils::PointPair &b_edge_pair)
boost::tuple< pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr > CoefficientsTriple
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
virtual double evaluatePointOnPlanes(const pcl::PointCloud< pcl::PointXYZRGB > &cloud, jsk_recognition_utils::ConvexPolygon &polygon_a, jsk_recognition_utils::ConvexPolygon &polygon_b)
virtual void estimate(const pcl::PointCloud< pcl::PointXYZRGB > &cloud)
boost::tuple< pcl::PointIndices::Ptr, pcl::PointIndices::Ptr > IndicesPair
message_filters::Subscriber< jsk_recognition_msgs::ParallelEdgeArray > sub_edges_
ros::Publisher pub_pose_array_
double convex_area_threshold_
const IndicesPair indices_pair_
void output(int index, double value)
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ParallelEdgeArray > SyncPolicy
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
jsk_pcl_ros::EdgebasedCubeFinderConfig Config
double outlier_threshold_
const CoefficientsPair coefficients_pair_
boost::mutex mutex
global mutex.
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
virtual jsk_recognition_utils::Cube::Ptr getCube()
double outlier_threshold_
virtual void computeCentroid(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointIndices::Ptr &indices, Eigen::Vector3f &output)
boost::shared_ptr< DiagnoalCubeHypothesis > Ptr
boost::tuple< Point, Point > PointPair
boost::tuple< IndicesTriple, CoefficientsTriple > IndicesCoefficientsTriple
boost::tuple< pcl::PointIndices::Ptr, pcl::PointIndices::Ptr, pcl::PointIndices::Ptr > IndicesTriple
double convex_edge_threshold_
CubeHypothesis(const IndicesPair &pair, const CoefficientsPair &coefficients_pair, const double outlier_threshold)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
jsk_recognition_utils::Cube::Ptr cube_
ros::Publisher pub_debug_polygons_
boost::shared_ptr< CubeHypothesis > Ptr
virtual ~CubeHypothesis()