36 #define BOOST_PARAMETER_MAX_ARITY 7 46 DiagnosticNodelet::onInit();
56 pub_polygons_ = advertise<jsk_recognition_msgs::PolygonArray>(
57 *
pnh_,
"output/polygons", 1);
59 *
pnh_,
"output/coefficients", 1);
61 pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
62 *
pnh_,
"output/indices", 1);
69 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(
queue_size_);
91 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons_msg)
93 jsk_recognition_msgs::ClusterPointIndices indices;
94 indices.header.stamp = polygons_msg->header.stamp;
95 indices.cluster_indices.resize(polygons_msg->polygons.size());
97 boost::make_shared<jsk_recognition_msgs::ClusterPointIndices>(indices));
101 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons_msg,
102 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
103 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
106 if (polygons_msg->polygons.size() != coefficients_msg->coefficients.size()) {
107 NODELET_ERROR(
"The size of polygons and coefficients are not same");
110 jsk_recognition_msgs::PolygonArray flipped_polygons = *polygons_msg;
111 jsk_recognition_msgs::ModelCoefficientsArray flipped_coefficients;
112 jsk_recognition_msgs::ClusterPointIndices flipped_indices;
113 flipped_polygons.polygons.clear();
114 flipped_coefficients.header = coefficients_msg->header;
115 flipped_indices.header = indices_msg->header;
117 for (
size_t i = 0; i < polygons_msg->polygons.size(); i++) {
118 geometry_msgs::PolygonStamped target_polygon = polygons_msg->polygons[i];
120 PCLIndicesMsg target_indices = indices_msg->cluster_indices[i];
126 Eigen::Affine3f sensor_transform;
131 Eigen::Vector3f polygon_normal = convex.
getNormal();
132 if (polygon_normal.dot(Eigen::Vector3f(sensor_transform.translation()))
134 geometry_msgs::PolygonStamped flipped_polygon;
136 target_polygon.polygon.points.begin(),
137 target_polygon.polygon.points.end(),
138 std::back_inserter(flipped_polygon.polygon.points));
139 flipped_polygon.header = target_polygon.header;
140 flipped_polygons.polygons.push_back(flipped_polygon);
143 flipped_polygons.polygons.push_back(target_polygon);
149 Eigen::Vector3f local_normal(target_coefficients.values[0],
150 target_coefficients.values[1],
151 target_coefficients.values[2]);
152 if (local_normal.dot(Eigen::Vector3f(sensor_transform.translation()))
156 for (
size_t j = 0; j < target_coefficients.values.size(); j++) {
157 the_flipped_coefficients.values.push_back(
158 - target_coefficients.values[j]);
160 std::reverse_copy(target_indices.indices.begin(), target_indices.indices.end(),
161 std::back_inserter(the_flipped_indices.indices));
162 the_flipped_coefficients.header = target_coefficients.header;
163 the_flipped_indices.header = target_indices.header;
164 flipped_coefficients.coefficients.push_back(the_flipped_coefficients);
166 flipped_indices.cluster_indices.push_back(the_flipped_indices);
171 flipped_coefficients.coefficients.push_back(target_coefficients);
172 flipped_indices.cluster_indices.push_back(target_indices);
182 NODELET_ERROR(
"Failed to lookup transformation: %s", e.what());
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void unsubscribe()
#define NODELET_ERROR(...)
static ConvexPolygon fromROSMsg(const geometry_msgs::Polygon &polygon)
void publish(const boost::shared_ptr< M > &message) const
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
virtual void flip(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
ros::Publisher pub_polygons_
std::string sensor_frame_
ros::Publisher pub_indices_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonFlipper, nodelet::Nodelet)
virtual void fillEmptyIndices(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg)
message_filters::PassThrough< jsk_recognition_msgs::ClusterPointIndices > sub_indices_null_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
tf::TransformListener * tf_listener_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
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)
ros::Publisher pub_coefficients_
void add(const MConstPtr &msg)
static tf::TransformListener * getInstance()
#define NODELET_FATAL(...)
pcl::PointIndices PCLIndicesMsg
pcl::ModelCoefficients PCLModelCoefficientMsg
virtual Eigen::Vector3f getNormal()
Connection registerCallback(const C &callback)