36 #define BOOST_PARAMETER_MAX_ARITY 7 44 DiagnosticNodelet::onInit();
45 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
46 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
48 srv_->setCallback (f);
50 pub_ = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"output", 1);
51 pub_xyz_ = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"output_xyz", 1);
60 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
72 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
73 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
75 if (polygon_msg->polygons.size() == 0) {
79 if (coefficients_msg->coefficients.size() != polygon_msg->polygons.size()) {
80 NODELET_ERROR(
"The size of coefficients and polygons are not same");
84 std::string
frame_id = polygon_msg->header.frame_id;
85 for (
size_t i = 0; i < polygon_msg->polygons.size(); i++) {
86 if (frame_id != polygon_msg->polygons[i].header.frame_id) {
89 polygon_msg->polygons[i].header.frame_id.c_str());
93 for (
size_t i = 0; i < coefficients_msg->coefficients.size(); i++) {
94 if (frame_id != coefficients_msg->coefficients[i].header.frame_id) {
97 coefficients_msg->coefficients[i].header.frame_id.c_str());
105 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
106 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
115 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr
cloud (
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
116 pcl::PointCloud<pcl::PointXYZ>::Ptr xyz_cloud (
new pcl::PointCloud<pcl::PointXYZ>);
117 for (
size_t i = 0; i < polygon_msg->polygons.size(); i++) {
120 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr one_cloud
122 pcl::PointCloud<pcl::PointXYZ> one_xyz_cloud;
123 one_xyz_cloud.points.resize(one_cloud->points.size());
124 for (
size_t i = 0; i < one_cloud->points.size(); i++) {
126 p.getVector3fMap() = one_cloud->points[i].getVector3fMap();
127 one_xyz_cloud.points[i] = p;
129 *xyz_cloud = *xyz_cloud + one_xyz_cloud;
130 *cloud = *cloud + *one_cloud;
132 sensor_msgs::PointCloud2 ros_cloud;
134 ros_cloud.header = polygon_msg->header;
136 sensor_msgs::PointCloud2 ros_xyz_cloud;
138 ros_xyz_cloud.header = polygon_msg->header;
virtual void unsubscribe()
virtual void configCallback(Config &config, uint32_t level)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
virtual void sample(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
static Polygon fromROSMsg(const geometry_msgs::Polygon &polygon)
PolygonPointsSamplerConfig Config
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonPointsSampler, nodelet::Nodelet)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
virtual bool isValidMessage(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
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)
pcl::PointCloud< PointT >::Ptr samplePoints(double grid_size)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
#define NODELET_DEBUG(...)