36 #define BOOST_PARAMETER_MAX_ARITY 7
45 DiagnosticNodelet::onInit();
46 pcl::console::setVerbosityLevel(pcl::console::L_ALWAYS);
48 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
49 dynamic_reconfigure::Server<Config>::CallbackType
f =
52 srv_->setCallback (
f);
54 pub_ = advertise<jsk_recognition_msgs::BoolStamped>(*pnh_,
"output", 1);
76 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> > (100);
80 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> > (100);
101 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg)
104 vital_checker_->poke();
107 NODELET_ERROR(
"frame_id does not match: cloud: %s, polygon: %s",
108 cloud_msg->header.frame_id.c_str(), polygon_msg->header.frame_id.c_str());
111 pcl::PointCloud<pcl::PointXYZ>::Ptr
cloud(
new pcl::PointCloud<pcl::PointXYZ>);
114 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>
polygons;
115 for (
size_t i = 0;
i < polygon_msg->polygons.size();
i++) {
119 for (
size_t i = 0;
i < polygon_msg->polygons.size();
i++) {
121 for (
size_t j = 0; j <
cloud->points.size(); j++) {
122 Eigen::Vector3f
p =
cloud->points[j].getVector3fMap();
137 jsk_recognition_msgs::BoolStamped bool_stamped;
138 bool_stamped.header =
header;
139 bool_stamped.data = v;