43 ConnectionBasedNodelet::onInit();
45 *pnh_,
"output_polygon", 1);
47 = advertise<pcl_msgs::ModelCoefficients>(
49 "output_coefficients", 1);
50 srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
51 dynamic_reconfigure::Server<Config>::CallbackType
f =
70 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
74 sync_->registerCallback(boost::bind(
93 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
94 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients)
99 if (selected_index >=
polygons->polygons.size()) {
101 selected_index =
polygons->polygons.size() - 1;
105 selected_index = std::distance(
107 std::max_element(
polygons->likelihood.begin(),
polygons->likelihood.end()));
109 geometry_msgs::PolygonStamped polygon_msg =
polygons->polygons[selected_index];
110 pcl_msgs::ModelCoefficients coefficients_msg =
coefficients->coefficients[selected_index];