37 #include <visualization_msgs/Marker.h>
38 #include <pcl/sample_consensus/method_types.h>
39 #include <pcl/sample_consensus/model_types.h>
40 #include <pcl/segmentation/sac_segmentation.h>
41 #include <pcl/filters/extract_indices.h>
42 #include <jsk_topic_tools/color_utils.h>
48 pcl::PointIndices::Ptr indices,
49 pcl::ModelCoefficients::Ptr coefficients):
55 const std_msgs::Header& input_header,
56 pcl::PointIndices::Ptr indices,
57 pcl::ModelCoefficients::Ptr coefficients,
58 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud):
64 pcl::ProjectInliers<pcl::PointXYZ> proj;
65 proj.setInputCloud(cloud);
66 proj.setIndices(indices);
67 proj.setModelType(pcl::SACMODEL_LINE);
68 proj.setModelCoefficients(coefficients);
70 pcl::ExtractIndices<pcl::PointXYZ>
ex;
71 ex.setInputCloud(cloud);
72 ex.setIndices(indices);
87 Eigen::Vector3f direction;
92 points_->points[0].getVector3fMap()));
101 visualization_msgs::Marker& marker,
102 const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
103 const double minimum_line_length)
106 int min_index = INT_MAX;
107 int max_index = - INT_MAX;
110 if (min_index >
index) {
113 if (max_index < index) {
117 geometry_msgs::Point
a,
b;
118 jsk_recognition_utils::pointFromXYZToXYZ<pcl::PointXYZ, geometry_msgs::Point>(
119 cloud->points[min_index], a);
120 jsk_recognition_utils::pointFromXYZToXYZ<pcl::PointXYZ, geometry_msgs::Point>(
121 cloud->points[max_index], b);
122 if (std::sqrt((
a.x -
b.x) * (
a.x -
b.x) +
123 (
a.y -
b.y) * (
a.y -
b.y) +
124 (
a.z -
b.z) * (
a.z -
b.z)) < minimum_line_length) {
127 marker.points.push_back(a);
128 marker.points.push_back(b);
134 DiagnosticNodelet::onInit();
138 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (
config_mutex_, *pnh_);
139 dynamic_reconfigure::Server<Config>::CallbackType
f =
141 srv_->setCallback (
f);
147 *pnh_,
"debug/line_marker", 1);
148 pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
149 *pnh_,
"output/inliers", 1);
151 *pnh_,
"output/coefficients", 1);
167 seg_.setOptimizeCoefficients (
true);
168 seg_.setModelType(pcl::SACMODEL_LINE);
169 int segmentation_method;
172 segmentation_method =
config.method_type;
174 seg_.setMethodType(segmentation_method);
184 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(100);
190 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
204 const std_msgs::Header&
header,
205 const pcl::PointCloud<PointT>::Ptr& cloud,
206 const std::vector<LineSegment::Ptr>& segments)
208 std::vector<pcl::PointIndices::Ptr> indices;
210 visualization_msgs::Marker
marker;
212 marker.pose.orientation.w = 1.0;
214 marker.type = visualization_msgs::Marker::LINE_LIST;
217 for (
size_t i = 0;
i < segments.size();
i++) {
220 indices.push_back(segments[
i]->getIndices());
222 std_msgs::ColorRGBA color = jsk_topic_tools::colorCategory20(
i);
224 marker.colors.push_back(color);
225 marker.colors.push_back(color);
228 jsk_recognition_msgs::ModelCoefficientsArray ros_coefficients;
229 jsk_recognition_msgs::ClusterPointIndices ros_indices;
230 ros_coefficients.header =
header;
231 ros_indices.header =
header;
232 ros_coefficients.coefficients
235 ros_indices.cluster_indices
244 const pcl::PointCloud<PointT>::Ptr& cloud,
245 const pcl::PointIndices::Ptr& indices,
246 std::vector<pcl::PointIndices::Ptr>& line_indices,
247 std::vector<pcl::ModelCoefficients::Ptr>& line_coefficients)
250 pcl::PointIndices::Ptr rest_indices (
new pcl::PointIndices);
251 rest_indices->indices = indices->indices;
253 seg_.setInputCloud(cloud);
256 pcl::PointIndices::Ptr
257 result_indices (
new pcl::PointIndices);
258 pcl::ModelCoefficients::Ptr
259 result_coefficients (
new pcl::ModelCoefficients);
260 seg_.setIndices(rest_indices);
261 seg_.segment(*result_indices, *result_coefficients);
263 line_indices.push_back(result_indices);
264 line_coefficients.push_back(result_coefficients);
279 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
280 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cluster_msg)
282 pcl::PointCloud<PointT>::Ptr
cloud(
new pcl::PointCloud<PointT>);
284 std::vector<LineSegment::Ptr> segments;
285 std::vector<pcl::PointIndices::Ptr> input_indices
288 for (
size_t i = 0;
i < cluster_msg->cluster_indices.size();
i++) {
289 std::vector<pcl::PointIndices::Ptr> line_indices;
290 std::vector<pcl::ModelCoefficients::Ptr> line_coefficients;
292 line_indices, line_coefficients);
293 if (line_indices.size() > 0) {
295 for (
size_t j = 0; j < line_indices.size(); j++) {
298 line_coefficients[j])));