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 =
58 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
62 sync_->registerCallback(boost::bind(
81 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
82 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients)
85 if (polygons->polygons.size() > 0) {
87 if (selected_index >= polygons->polygons.size()) {
89 selected_index = polygons->polygons.size() - 1;
93 selected_index = std::distance(
94 polygons->likelihood.begin(),
95 std::max_element(polygons->likelihood.begin(), polygons->likelihood.end()));
97 geometry_msgs::PolygonStamped polygon_msg = polygons->polygons[selected_index];
98 pcl_msgs::ModelCoefficients coefficients_msg = coefficients->coefficients[selected_index];
PolygonArrayUnwrapperConfig Config
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
#define NODELET_ERROR_THROTTLE(rate,...)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonArrayUnwrapper, nodelet::Nodelet)
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
virtual void unwrap(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients)
virtual void configCallback(Config &config, uint32_t level)
virtual void unsubscribe()
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
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)
ros::Publisher pub_polygon_
ros::Publisher pub_coefficients_