46 ConnectionBasedNodelet::onInit();
47 if (!pnh_->getParam(
"frame_id",
frame_id_)) {
52 polygons_pub_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_,
"output_polygons", 1);
54 *pnh_,
"output_coefficients", 1);
71 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
87 Eigen::Vector3d
A, B, C;
88 A[0] = polygon.polygon.points[0].x;
89 A[1] = polygon.polygon.points[0].y;
90 A[2] = polygon.polygon.points[0].z;
91 B[0] = polygon.polygon.points[1].x;
92 B[1] = polygon.polygon.points[1].y;
93 B[2] = polygon.polygon.points[1].z;
94 C[0] = polygon.polygon.points[2].x;
95 C[1] = polygon.polygon.points[2].y;
96 C[2] = polygon.polygon.points[2].z;
97 Eigen::Vector3d n = (B -
A).
cross(C -
A).normalized();
101 double d = -(
a *
A[0] +
b *
A[1] + c *
A[2]);
102 coefficient.header = polygon.header;
103 coefficient.values.push_back(a);
104 coefficient.values.push_back(b);
105 coefficient.values.push_back(c);
106 coefficient.values.push_back(d);
116 result.header.stamp = coefficient.header.stamp;
120 coefficient.values[0], coefficient.values[1], coefficient.values[2], coefficient.values[3],
121 result.values[0], result.values[1], result.values[2], result.values[3]);
125 const geometry_msgs::PolygonStamped& polygon,
126 geometry_msgs::PolygonStamped& result)
128 result.header = polygon.header;
130 for (
size_t i = 0;
i < polygon.polygon.points.size();
i++) {
131 Eigen::Vector4d
point;
132 point[0] = polygon.polygon.points[
i].x;
133 point[1] = polygon.polygon.points[
i].y;
134 point[2] = polygon.polygon.points[
i].z;
136 Eigen::Vector4d transformed_point_eigen =
transform.inverse() *
point;
137 geometry_msgs::Point32 transformed_point;
138 transformed_point.x = transformed_point_eigen[0];
139 transformed_point.y = transformed_point_eigen[1];
140 transformed_point.z = transformed_point_eigen[2];
141 result.polygon.points.push_back(transformed_point);
146 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients)
149 NODELET_ERROR(
"the size of polygons(%lu) does not match with the size of coefficients(%lu)",
155 jsk_recognition_msgs::PolygonArray transformed_polygon_array;
156 jsk_recognition_msgs::ModelCoefficientsArray transformed_model_coefficients_array;
157 transformed_polygon_array.header =
polygons->header;
158 transformed_model_coefficients_array.header =
coefficients->header;
159 transformed_polygon_array.header.frame_id =
frame_id_;
160 transformed_model_coefficients_array.header.frame_id =
frame_id_;
161 for (
size_t i = 0;
i <
polygons->polygons.size();
i++) {
162 geometry_msgs::PolygonStamped polygon =
polygons->polygons[
i];
165 if (polygon.header.frame_id != coefficient.header.frame_id) {
166 NODELET_ERROR(
"frame_id of polygon[%lu] is %s and frame_id of coefficient[%lu] is %s, they does not point to the same frame_id",
167 i, polygon.header.frame_id.c_str(),
168 i, coefficient.header.frame_id.c_str());
173 coefficient.header.stamp,
177 coefficient.header.stamp)) {
182 Eigen::Affine3d eigen_transform;
187 geometry_msgs::PolygonStamped transformed_polygon;
188 if (polygon.polygon.points.size() == 0) {
189 transformed_polygon.header = polygon.header;
190 transformed_polygon.header.frame_id =
frame_id_;
191 transformed_polygon_array.polygons.push_back(transformed_polygon);
192 transformed_coefficient.values = coefficient.values;
193 transformed_coefficient.header = polygon.header;
194 transformed_coefficient.header.frame_id =
frame_id_;
195 transformed_model_coefficients_array.coefficients.push_back(transformed_coefficient);
201 transformed_coefficient);
202 if (isnan(transformed_coefficient.values[0]) ||
203 isnan(transformed_coefficient.values[1]) ||
204 isnan(transformed_coefficient.values[2]) ||
205 isnan(transformed_coefficient.values[3])) {
208 transformed_polygon_array.polygons.push_back(transformed_polygon);
209 transformed_model_coefficients_array.coefficients.push_back(transformed_coefficient);
214 frame_id_.c_str(), coefficient.header.frame_id.c_str(),
215 coefficient.header.stamp.toSec());