38 #include <jsk_recognition_msgs/ParallelEdgeArray.h> 44 ConnectionBasedNodelet::onInit();
49 pub_ = advertise<jsk_recognition_msgs::ParallelEdgeArray>(*
pnh_,
"output_edges_groups", 1);
50 pub_clusters_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*
pnh_,
"output_clusters", 1);
55 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
56 dynamic_reconfigure::Server<Config>::CallbackType
f =
58 srv_->setCallback (f);
69 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
82 Config &config, uint32_t level)
89 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
90 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients)
96 std::vector<jsk_recognition_utils::Line::Ptr>
lines;
97 if (input_coefficients->coefficients.size() == 0) {
100 for (
size_t i = 0; i < input_coefficients->coefficients.size(); i++) {
101 std::vector<float> the_coefficients
102 = input_coefficients->coefficients[i].values;
106 std::map<int, std::vector<int> > parallel_map;
107 for (
size_t i = 0; i < lines.size() - 1; i++) {
108 parallel_map[i] = std::vector<int>();
110 for (
size_t j = i + 1; j < lines.size(); j++) {
113 parallel_map[i].push_back(j);
120 std::vector<std::set<int> > parallel_groups_list;
124 std::set<int> listed_indices;
126 for (
size_t i = 0; i < lines.size() - 1; i++) {
127 std::vector<int> parallel_indices = parallel_map[i];
128 if (listed_indices.find(i) == listed_indices.end()) {
129 if (parallel_indices.size() == 0) {
133 std::set<int> new_parallel_set;
138 parallel_groups_list.push_back(new_parallel_set);
144 publishResult(parallel_groups_list, input_indices, input_coefficients);
150 const std::vector<std::set<int> >& parallel_groups_list,
151 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
152 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients)
154 jsk_recognition_msgs::ParallelEdgeArray ros_output_msg;
155 ros_output_msg.header = input_indices->header;
156 for (
size_t i = 0; i < parallel_groups_list.size(); i++) {
157 std::set<int> parallel_groups = parallel_groups_list[i];
158 jsk_recognition_msgs::ParallelEdge edge_group;
159 edge_group.header = input_indices->header;
160 for (std::set<int>::iterator it = parallel_groups.begin();
161 it != parallel_groups.end();
164 std::vector<int> indices
165 = input_indices->cluster_indices[the_index].indices;
167 = input_coefficients->coefficients[the_index].values;
169 indices_msg.header = input_indices->header;
170 indices_msg.indices = indices;
172 coefficients_msg.header = input_coefficients->header;
173 coefficients_msg.values = coefficients;
174 edge_group.cluster_indices.push_back(indices_msg);
175 edge_group.coefficients.push_back(coefficients_msg);
177 ros_output_msg.edge_groups.push_back(edge_group);
183 const std::vector<std::set<int> >& parallel_groups_list,
184 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
185 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients)
187 jsk_recognition_msgs::ClusterPointIndices ros_output_msg;
188 ros_output_msg.header = input_indices->header;
190 for (
size_t i = 0; i < parallel_groups_list.size(); i++) {
191 std::set<int> parallel_groups = parallel_groups_list[i];
193 indices_msg.header = input_indices->header;
194 for (std::set<int>::iterator it = parallel_groups.begin();
195 it != parallel_groups.end();
199 input_indices->cluster_indices[*it].indices);
201 ros_output_msg.cluster_indices.push_back(indices_msg);
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
virtual void unsubscribe()
jsk_pcl_ros::ParallelEdgeFinderConfig Config
virtual void configCallback(Config &config, uint32_t level)
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher pub_clusters_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void publishResultAsCluser(const std::vector< std::set< int > > ¶llel_groups_list, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &input_coefficients)
std::vector< int > addIndices(const std::vector< int > &a, const std::vector< int > &b)
static Ptr fromCoefficients(const std::vector< float > &coefficients)
virtual void publishResult(const std::vector< std::set< int > > ¶llel_groups_list, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &input_coefficients)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void buildGroupFromGraphMap(IntegerGraphMap graph_map, const int from_index, std::vector< int > &to_indices, std::set< int > &output_set)
void addSet(std::set< T > &output, const std::set< T > &new_set)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
pcl::PointIndices PCLIndicesMsg
pcl::ModelCoefficients PCLModelCoefficientMsg
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ParallelEdgeFinder, nodelet::Nodelet)
virtual void estimate(const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &input_coefficients)