42 ConnectionBasedNodelet::onInit();
44 "output_polygons", 1);
46 = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*
pnh_,
47 "output_coefficients", 1);
52 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
56 sync_->registerCallback(boost::bind(
68 const geometry_msgs::PolygonStamped::ConstPtr& polygon,
69 const pcl_msgs::ModelCoefficients::ConstPtr& coefficients)
71 jsk_recognition_msgs::PolygonArray array_msg;
72 array_msg.header = polygon->header;
73 geometry_msgs::PolygonStamped new_polygon(*polygon);
74 array_msg.polygons.push_back(new_polygon);
77 jsk_recognition_msgs::ModelCoefficientsArray coefficients_array;
78 coefficients_array.header = coefficients->header;
79 pcl_msgs::ModelCoefficients new_coefficients(*coefficients);
80 coefficients_array.coefficients.push_back(new_coefficients);
ros::Publisher pub_polygon_array_
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher pub_coefficients_array_
virtual void unsubscribe()
virtual void wrap(const geometry_msgs::PolygonStamped::ConstPtr &polygon, const pcl_msgs::ModelCoefficients::ConstPtr &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)
message_filters::Subscriber< pcl_msgs::ModelCoefficients > sub_coefficients_
message_filters::Subscriber< geometry_msgs::PolygonStamped > sub_polygon_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonArrayWrapper, nodelet::Nodelet)