Go to the documentation of this file.
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>
63 #include <jsk_topic_tools/connection_based_nodelet.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,
108 const pcl::PointIndices::Ptr& indices,
109 Eigen::Vector3f& output);
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)
143 class DiagnoalCubeHypothesis:
public CubeHypothesis
149 const double outlier_threshold);
150 virtual void estimate(
const pcl::PointCloud<pcl::PointXYZRGB>& cloud);
161 sensor_msgs::PointCloud2,
162 jsk_recognition_msgs::ParallelEdgeArray >
SyncPolicy;
164 typedef jsk_pcl_ros::EdgebasedCubeFinderConfig
Config;
182 const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
183 const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr& input_edges);
185 const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
186 const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr& input_edges);
194 const std::vector<pcl::PointIndices::Ptr>& indices);
197 const std::vector<pcl::ModelCoefficients::Ptr>& coefficients);
200 const Eigen::Vector3f& a,
201 const Eigen::Vector3f& b);
203 virtual std::vector<IndicesCoefficientsTriple>
205 const std::vector<pcl::PointIndices::Ptr>& indices,
206 const std::vector<pcl::ModelCoefficients::Ptr>& coefficients);
214 virtual std::vector<IndicesCoefficientsTriple>
216 const std::vector<IndicesCoefficientsTriple>& triples);
222 const pcl::PointCloud<PointT>::Ptr cloud,
226 const pcl::PointCloud<PointT>::Ptr cloud,
229 const pcl::PointCloud<PointT>::Ptr cloud,
230 const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes,
231 std::vector<int>& output_indices);
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);
244 const pcl::PointCloud<PointT>::Ptr cloud,
245 const pcl::PointIndices::Ptr indices);
249 const pcl::PointCloud<PointT>::Ptr cloud);
253 const pcl::PointCloud<PointT>::Ptr filtered_cloud,
254 pcl::PointIndices::Ptr output_inliers,
255 pcl::ModelCoefficients::Ptr output_coefficients);
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
269 const pcl::PointCloud<PointT>::Ptr cloud);
273 const pcl::PointCloud<PointT>::Ptr cloud,
274 const pcl::PointIndices::Ptr indices,
275 pcl::ModelCoefficients::Ptr coefficients,
276 pcl::PointIndices::Ptr inliers);
boost::tuple< pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr > CoefficientsPair
virtual jsk_recognition_utils::PointPair minMaxPointOnLine(const jsk_recognition_utils::Line &line, const pcl::PointCloud< PointT >::Ptr cloud)
ros::Publisher pub_debug_polygons_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ParallelEdgeArray > SyncPolicy
double convex_edge_threshold_
virtual jsk_recognition_utils::ConvexPolygon::Ptr buildConvexPolygon(const jsk_recognition_utils::PointPair &a_edge_pair, const jsk_recognition_utils::PointPair &b_edge_pair)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void estimate(const pcl::PointCloud< pcl::PointXYZRGB > &cloud)=0
virtual double evaluatePointOnPlanes(const pcl::PointCloud< pcl::PointXYZRGB > &cloud, jsk_recognition_utils::ConvexPolygon &polygon_a, jsk_recognition_utils::ConvexPolygon &polygon_b)
virtual jsk_recognition_utils::Cube::Ptr cubeFromIndicesAndCoefficients(const pcl::PointCloud< PointT >::Ptr cloud, const IndicesCoefficientsTriple &indices_coefficients_triple, pcl::PointCloud< EdgebasedCubeFinder::PointT >::Ptr points_on_edge)
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 int countInliers(const pcl::PointCloud< PointT >::Ptr cloud, const jsk_recognition_utils::ConvexPolygon::Ptr convex)
virtual void filterPairsBasedOnParallelEdgeDistances(const std::vector< IndicesPair > &pairs, const std::vector< CoefficientsPair > &coefficients_pair, std::vector< IndicesPair > &filtered_indices_pairs, std::vector< CoefficientsPair > &filtered_coefficients_pairs)
boost::tuple< pcl::PointIndices::Ptr, pcl::PointIndices::Ptr > IndicesPair
message_filters::Subscriber< jsk_recognition_msgs::ParallelEdgeArray > sub_edges_
virtual void estimate(const pcl::PointCloud< pcl::PointXYZRGB > &cloud)
virtual ~CubeHypothesis()
CubeHypothesis(const IndicesPair &pair, const CoefficientsPair &coefficients_pair, const double outlier_threshold)
virtual std::vector< CoefficientsPair > combinateCoefficients(const std::vector< pcl::ModelCoefficients::Ptr > &coefficients)
virtual void filterBasedOnConvex(const pcl::PointCloud< PointT >::Ptr cloud, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes, std::vector< int > &output_indices)
double outlier_threshold_
virtual void computeCentroid(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointIndices::Ptr &indices, Eigen::Vector3f &output)
virtual bool isPerpendicularVector(const Eigen::Vector3f &a, const Eigen::Vector3f &b)
double outlier_threshold_
virtual EdgeRelation perpendicularEdgeTriple(const jsk_recognition_utils::Line &edge_a, const jsk_recognition_utils::Line &edge_b, const jsk_recognition_utils::Line &edge_c)
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr &input_edges)
virtual void estimate(const pcl::PointCloud< pcl::PointXYZRGB > &cloud)
jsk_pcl_ros::EdgebasedCubeFinderConfig Config
double parallel_edge_distance_max_threshold_
double parallel_edge_distance_min_threshold_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
boost::shared_ptr< PlanarCubeHypothesis > Ptr
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 jsk_recognition_utils::Line::Ptr midLineFromCoefficientsPair(const CoefficientsPair &pair)
ros::Publisher pub_pose_array_
const CoefficientsPair coefficients_pair_
virtual std::vector< IndicesCoefficientsTriple > filterPerpendicularEdgeTriples(const std::vector< IndicesCoefficientsTriple > &triples)
boost::tuple< IndicesTriple, CoefficientsTriple > IndicesCoefficientsTriple
virtual jsk_recognition_utils::ConvexPolygon::Ptr estimateConvexPolygon(const pcl::PointCloud< PointT >::Ptr cloud, const pcl::PointIndices::Ptr indices, pcl::ModelCoefficients::Ptr coefficients, pcl::PointIndices::Ptr inliers)
virtual void configCallback(Config &config, uint32_t level)
virtual std::vector< IndicesCoefficientsTriple > tripleIndicesAndCoefficients(const std::vector< pcl::PointIndices::Ptr > &indices, const std::vector< pcl::ModelCoefficients::Ptr > &coefficients)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual jsk_recognition_utils::ConvexPolygon::Ptr convexFromPairs(const pcl::PointCloud< PointT >::Ptr cloud, const CoefficientsPair &coefficients_pair, const IndicesPair &indices_pair)
virtual pcl::PointIndices::Ptr preparePointCloudForRANSAC(const jsk_recognition_utils::ConvexPolygon::Ptr convex, const CoefficientsPair &edge_coefficients_pair, const pcl::PointCloud< PointT >::Ptr cloud)
virtual void unsubscribe()
double convex_area_threshold_
virtual jsk_recognition_utils::Cube::Ptr getCube()
virtual ~EdgebasedCubeFinder()
virtual std::vector< IndicesPair > combinateIndices(const std::vector< pcl::PointIndices::Ptr > &indices)
PlanarCubeHypothesis(const IndicesPair &pair, const CoefficientsPair &coefficients_pair, const double outlier_threshold)
virtual pcl::PointCloud< PointT >::Ptr extractPointCloud(const pcl::PointCloud< PointT >::Ptr cloud, const pcl::PointIndices::Ptr indices)
boost::mutex mutex
global mutex.
const IndicesPair indices_pair_
boost::tuple< pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr, pcl::ModelCoefficients::Ptr > CoefficientsTriple
boost::shared_ptr< DiagnoalCubeHypothesis > Ptr
DiagnoalCubeHypothesis(const IndicesPair &pair, const CoefficientsPair &coefficients_pair, const double outlier_threshold)
boost::tuple< Point, Point > PointPair
virtual double getValue()
virtual void estimateParallelPlane(const jsk_recognition_utils::ConvexPolygon::Ptr convex, const pcl::PointCloud< PointT >::Ptr filtered_cloud, pcl::PointIndices::Ptr output_inliers, pcl::ModelCoefficients::Ptr output_coefficients)
jsk_recognition_utils::Cube::Ptr cube_
ros::Publisher pub_debug_clusers_
virtual void estimatePerpendicularPlane(const jsk_recognition_utils::ConvexPolygon::Ptr convex, const CoefficientsPair &edge_coefficients, const pcl::PointCloud< PointT >::Ptr filtered_cloud, pcl::PointIndices::Ptr output_inliers, pcl::ModelCoefficients::Ptr output_coefficients)
ros::Publisher pub_debug_filtered_cloud_
boost::shared_ptr< CubeHypothesis > Ptr
boost::tuple< pcl::PointIndices::Ptr, pcl::PointIndices::Ptr, pcl::PointIndices::Ptr > IndicesTriple
virtual void estimate2(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr &input_edges)
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
ros::Publisher pub_debug_marker_
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44