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);
64 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> > (100);
68 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> > (100);
89 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg)
95 NODELET_ERROR(
"frame_id does not match: cloud: %s, polygon: %s",
96 cloud_msg->header.frame_id.c_str(), polygon_msg->header.frame_id.c_str());
99 pcl::PointCloud<pcl::PointXYZ>::Ptr
cloud(
new pcl::PointCloud<pcl::PointXYZ>);
102 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>
polygons;
103 for (
size_t i = 0; i < polygon_msg->polygons.size(); i++) {
107 for (
size_t i = 0; i < polygon_msg->polygons.size(); i++) {
109 for (
size_t j = 0; j < cloud->points.size(); j++) {
110 Eigen::Vector3f
p = cloud->points[j].getVector3fMap();
125 jsk_recognition_msgs::BoolStamped bool_stamped;
126 bool_stamped.header = header;
127 bool_stamped.data = v;
virtual void unsubscribe()
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void predicate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
static ConvexPolygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon &polygon)
virtual void configCallback(Config &config, uint32_t level)
virtual void publishPredicate(const std_msgs::Header &header, const bool v)
jsk_recognition_utils::SeriesedBoolean::Ptr buffer_
CloudOnPlaneConfig Config
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
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)
bool isSameFrameId(const std::string &a, const std::string &b)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::CloudOnPlane, nodelet::Nodelet)