43 ConnectionBasedNodelet::onInit();
44 pub_polygon_ = advertise<jsk_recognition_msgs::PolygonArray>(*
pnh_,
"output", 1);
46 "output_coefficients", 1);
48 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy2> >(100);
71 const jsk_recognition_msgs::PolygonArray::ConstPtr& msg0,
72 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients0,
73 const jsk_recognition_msgs::PolygonArray::ConstPtr& msg1,
74 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients1)
76 std::vector<jsk_recognition_msgs::PolygonArray::ConstPtr> arrays;
77 arrays.push_back(msg0);
78 arrays.push_back(msg1);
79 std::vector<jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr> coefficients_array;
80 coefficients_array.push_back(coefficients0);
81 coefficients_array.push_back(coefficients1);
86 const std::vector<jsk_recognition_msgs::PolygonArray::ConstPtr>& arrays,
87 const std::vector<jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr>& coefficients_array)
89 if (arrays.size() == 0) {
93 if (coefficients_array.size() == 0) {
97 if (arrays.size() != coefficients_array.size()) {
98 NODELET_ERROR(
"polygons and coefficients are not the same length");
101 jsk_recognition_msgs::PolygonArray new_array;
102 new_array.header = arrays[0]->header;
103 for (
size_t i = 0; i < arrays.size(); i++) {
104 jsk_recognition_msgs::PolygonArray::ConstPtr array = arrays[i];
105 for (
size_t j = 0; j < array->polygons.size(); j++) {
106 geometry_msgs::PolygonStamped polygon = array->polygons[j];
107 new_array.polygons.push_back(polygon);
112 jsk_recognition_msgs::ModelCoefficientsArray coefficients_new_array;
113 coefficients_new_array.header = coefficients_array[0]->header;
114 for (
size_t i = 0; i < coefficients_array.size(); i++) {
115 jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr array = coefficients_array[i];
116 for (
size_t j = 0; j < array->coefficients.size(); j++) {
117 coefficients_new_array.coefficients.push_back(array->coefficients[j]);
#define NODELET_ERROR(...)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients1_
void publish(const boost::shared_ptr< M > &message) const
virtual void callback2(const jsk_recognition_msgs::PolygonArray::ConstPtr &msg0, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients0, const jsk_recognition_msgs::PolygonArray::ConstPtr &msg1, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients1)
ros::Publisher pub_coefficients_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonAppender, nodelet::Nodelet)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy2 > > sync_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon1_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon0_
ros::Publisher pub_polygon_
virtual void appendAndPublish(const std::vector< jsk_recognition_msgs::PolygonArray::ConstPtr > &arrays, const std::vector< jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr > &coefficients_array)
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)
virtual void unsubscribe()
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients0_