$search
00001 #include "ros/ros.h" 00002 #include <pcl/point_types.h> 00003 #include <pcl/point_cloud.h> 00004 #include <pcl/ros/conversions.h> 00005 #include <pcl/features/normal_3d.h> 00006 #include <pcl/point_representation.h> 00007 #include <pcl/kdtree/kdtree_flann.h> 00008 #include <pcl/io/pcd_io.h> 00009 00010 #include <sensor_msgs/PointCloud2.h> 00011 00012 #include <cob_3d_mapping_msgs/ShapeArray.h> 00013 #include <cob_3d_mapping_msgs/Shape.h> 00014 #include <cob_3d_mapping_common/polygon.h> 00015 00016 #include <ros/time.h> 00017 #include <math.h> 00018 #include <Eigen/Core> 00019 #include <boost/shared_ptr.hpp> 00020 00021 #define PI 3.14159265 00022 using namespace std; 00023 00024 void 00025 firstShape (cob_3d_mapping_msgs::Shape& s, Eigen::Vector3f normal, Eigen::Vector3f color) 00026 { 00027 pcl::PointXYZ pt; 00028 pcl::PointCloud<pcl::PointXYZ> pc; 00029 sensor_msgs::PointCloud2 pc2; 00030 00031 s.id = 0; 00032 00033 //first shape 00034 s.params[0] = normal[0]; 00035 s.params[1] = normal[1]; 00036 s.params[2] = normal[2]; 00037 s.params[3] = 0; 00038 00039 s.color.r = color[0]; 00040 s.color.g = color[1]; 00041 s.color.b = color[2]; 00042 s.color.a = 1; 00043 00044 float z = 2; 00045 00046 pt.x = 0.0; 00047 pt.y = 0.0; 00048 pt.z = z; 00049 pc.push_back (pt); 00050 00051 pt.x = 1.0; 00052 pt.y = 0.0; 00053 pt.z = z; 00054 pc.push_back (pt); 00055 00056 pt.x = 1.0; 00057 pt.y = 1.0; 00058 pt.z = z; 00059 pc.push_back (pt); 00060 00061 pt.x = 0.0; 00062 pt.y = 1.0; 00063 pt.z = z; 00064 pc.push_back (pt); 00065 00066 /* 00067 pt.x = 0.0; 00068 pt.y = 0.0; 00069 pt.z = z; 00070 pc.push_back (pt); 00071 */ 00072 Eigen::VectorXf centroid; 00073 pcl::computeNDCentroid (pc, centroid); 00074 //std::cout<<" centroid : "<<centroid<<"\n X: "<<centroid[0]<<"\n Y: "<<centroid[1]<<"\n Z: "<<centroid[2]<<std::endl; 00075 00076 s.centroid.x = centroid[0]; 00077 s.centroid.y = centroid[1]; 00078 s.centroid.z = centroid[2]; 00079 00080 pcl::toROSMsg (pc, pc2); 00081 s.points.push_back (pc2); 00082 } 00083 00084 void 00085 secondShape (cob_3d_mapping_msgs::Shape& s, Eigen::Vector3f normal, Eigen::Vector3f color) 00086 { 00087 pcl::PointXYZ pt; 00088 pcl::PointCloud<pcl::PointXYZ> pc; 00089 sensor_msgs::PointCloud2 pc2; 00090 00091 s.id = 1; 00092 00093 s.params[0] = normal[0]; 00094 s.params[1] = normal[1]; 00095 s.params[2] = normal[2]; 00096 s.params[3] = 0; 00097 00098 s.color.r = color[0]; 00099 s.color.g = color[1]; 00100 s.color.b = color[2]; 00101 s.color.a = 1; 00102 00103 pt.x = 0; 00104 pt.y = 0; 00105 pt.z = -1; 00106 pc.push_back (pt); 00107 00108 pt.x = 2; 00109 pt.y = 0; 00110 pt.z = -1; 00111 pc.push_back (pt); 00112 00113 pt.x = 2; 00114 pt.y = 2; 00115 pt.z = -1; 00116 pc.push_back (pt); 00117 00118 pt.x = 0; 00119 pt.y = 2; 00120 pt.z = 1; 00121 pc.push_back (pt); 00122 00123 /* 00124 pt.x = 2; 00125 pt.y = 2; 00126 pt.z = 2; 00127 pc.push_back (pt); 00128 */ 00129 Eigen::VectorXf centroid; 00130 pcl::computeNDCentroid (pc, centroid); 00131 //std::cout<<" centroid : "<<centroid<<"--> X: "<<centroid[0]<<"--> Y: "<<centroid[1]<<"--> Z: "<<centroid[2]<<std::endl; 00132 00133 s.centroid.x = centroid[0]; 00134 s.centroid.y = centroid[1]; 00135 s.centroid.z = centroid[2]; 00136 00137 pcl::toROSMsg (pc, pc2); 00138 s.points.push_back (pc2); 00139 } 00140 00141 void 00142 thirdShape (cob_3d_mapping_msgs::Shape& s, Eigen::Vector3f normal, Eigen::Vector3f color) 00143 { 00144 pcl::PointXYZ pt; 00145 pcl::PointCloud<pcl::PointXYZ> pc; 00146 sensor_msgs::PointCloud2 pc2; 00147 00148 s.id = 2; 00149 00150 s.params[0] = normal[0]; 00151 s.params[1] = normal[1]; 00152 s.params[2] = normal[2]; 00153 s.params[3] = 0; 00154 00155 s.color.r = color[0]; 00156 s.color.g = color[1]; 00157 s.color.b = color[2]; 00158 s.color.a = 1; 00159 00160 pt.x = -5; 00161 pt.y = -5; 00162 pt.z = -2; 00163 pc.push_back (pt); 00164 00165 pt.x = -5; 00166 pt.y = -1; 00167 pt.z = -2; 00168 pc.push_back (pt); 00169 00170 pt.x = -6; 00171 pt.y = -5; 00172 pt.z = -2; 00173 pc.push_back (pt); 00174 00175 Eigen::VectorXf centroid; 00176 pcl::computeNDCentroid (pc, centroid); 00177 //std::cout<<" centroid : "<<centroid<<"--> X: "<<centroid[0]<<"--> Y: "<<centroid[1]<<"--> Z: "<<centroid[2]<<std::endl; 00178 00179 s.centroid.x = centroid[0]; 00180 s.centroid.y = centroid[1]; 00181 s.centroid.z = centroid[2]; 00182 00183 pcl::toROSMsg (pc, pc2); 00184 s.points.push_back (pc2); 00185 } 00186 00187 void 00188 fourthShape (cob_3d_mapping_msgs::Shape& s, Eigen::Vector3f normal, Eigen::Vector3f color) 00189 { 00190 pcl::PointXYZ pt; 00191 pcl::PointCloud<pcl::PointXYZ> pc; 00192 sensor_msgs::PointCloud2 pc2; 00193 /* 00194 Eigen::Vector3f v2 (1, 0, 0), v3 (0, 0, 0), v4; 00195 //cout << " v1 : \n" << v1 << endl; 00196 //cout<< " v1 orthognal : \n"<<v1.unitOrthogonal()<<endl; 00197 //v1.normalize(); 00198 //cout<< " v1 norm : "<<v1<<endl; 00199 v2 = v1.unitOrthogonal (); 00200 //cout << " v2 : \n" << v2 << endl; 00201 //cout<< " v1 euler : \n"<<v1.eulerAngles(v1.de,1,2)<<endl; 00202 v3 = v2.unitOrthogonal (); 00203 //cout << " v3 : \n" << v3 << endl; 00204 00205 v4 = v3.unitOrthogonal (); 00206 //cout << " v4 : \n" << v3 << endl; 00207 //sixth shape 00208 */ 00209 00210 s.id = 3; 00211 s.params[0] = normal[0]; 00212 s.params[1] = normal[1]; 00213 s.params[2] = normal[2]; 00214 s.params[3] = 0; 00215 00216 s.color.r = color[0]; 00217 s.color.g = color[1]; 00218 s.color.b = color[2]; 00219 s.color.a = 1; 00220 /* 00221 int a = 4; 00222 00223 for (int i = 1; i < 4; i++) 00224 { 00225 if (i % 3 == 0) 00226 { 00227 pt.x = a * i * v2[0]; 00228 pt.y = i * v2[1]; 00229 } 00230 else 00231 { 00232 if (i % 2 == 0) 00233 pt.x = i * v2[0]; 00234 else 00235 pt.y = a * i * v2[1]; 00236 } 00237 pt.z = v2[2]; 00238 pc.push_back (pt); 00239 cout << " pt : \n" << pt << endl; 00240 } 00241 */ 00242 //int x = v2[0], y = v2[1], z = v2[2]; 00243 int x = 1, y = 0, z = 0; 00244 pt.x = x; 00245 pt.y = y; 00246 pt.z = z; 00247 pc.push_back (pt); 00248 00249 //x = v3[0], y = v3[1], z = v3[2]; 00250 x = 0, y = 1, z = 0; 00251 pt.x = x; 00252 pt.y = y; 00253 pt.z = z; 00254 pc.push_back (pt); 00255 00256 //x = v4[0], y = v4[1], z = v4[2]; 00257 x = 0, y = 0, z = 1; 00258 pt.x = x; 00259 pt.y = y; 00260 pt.z = z; 00261 pc.push_back (pt); 00262 00263 /* 00264 x = 1, y = 0, z = 1; 00265 pt.x = x; 00266 pt.y = y; 00267 pt.z = z; 00268 pc.push_back (pt); 00269 00270 x = v2[0], y = v2[1], z = v2[2]; 00271 pt.x = x; 00272 pt.y = y; 00273 pt.z = z; 00274 pc.push_back (pt); 00275 */ 00276 Eigen::VectorXf centroid; 00277 pcl::computeNDCentroid (pc, centroid); 00278 //std::cout << " centroid : \n" << centroid << std::endl; 00279 //std::cout << " point cloud : \n" << pc << std::endl; 00280 s.centroid.x = centroid[0]; 00281 s.centroid.y = centroid[1]; 00282 s.centroid.z = centroid[2]; 00283 pcl::toROSMsg (pc, pc2); 00284 s.points.push_back (pc2); 00285 00286 } 00287 00288 void 00289 fifthShape (cob_3d_mapping_msgs::Shape& s, Eigen::Vector3f normal, Eigen::Vector3f color) 00290 { 00291 pcl::PointXYZ pt; 00292 pcl::PointCloud<pcl::PointXYZ> pc; 00293 sensor_msgs::PointCloud2 pc2; 00294 00295 s.id = 4; 00296 00297 s.params[0] = normal[0]; 00298 s.params[1] = normal[1]; 00299 s.params[2] = normal[2]; 00300 s.params[3] = 0; 00301 00302 s.color.r = color[0]; 00303 s.color.g = color[1]; 00304 s.color.b = color[2]; 00305 s.color.a = 1; 00306 /* 00307 Eigen::Vector3f v2 (-normal[0], normal[1], -normal[2]), v3 (normal[0], -normal[1], normal[2]), v4 (normal[0], normal[1], -normal[2]); 00308 cout << " normal : \n" << normal << endl; 00309 cout << " v2 : \n" << v2 << endl; 00310 cout << " v3 : \n" << v3 << endl; 00311 cout << " v4 : \n" << v4 << endl; 00312 //cout<< " v1 orthognal : \n"<<v1.unitOrthogonal()<<endl; 00313 //v1.normalize(); 00314 //cout<< " v1 norm : "<<v1<<endl; 00315 //v2 = v1.unitOrthogonal (); 00316 cout << " v2.dot (normal) : \n" << v2.dot (normal) << endl; 00317 cout << " v3.dot (normal) : \n" << v3.dot (normal) << endl; 00318 cout << " v4.dot (normal) : \n" << v4.dot (normal) << endl; 00319 00320 //cout<< " v1 euler : \n"<<v1.eulerAngles(v1.de,1,2)<<endl; 00321 //v3 = v2.unitOrthogonal (); 00322 //cout << " v3 : \n" << v3 << endl; 00323 00324 //v4 = v3.unitOrthogonal (); 00325 //cout << " v4 : \n" << v3 << endl; 00326 //sixth shape 00327 */ 00328 float x = 0 , y = -1, z = 0; 00329 00330 pt.x = x; 00331 pt.y = y; 00332 pt.z = z; 00333 pc.push_back (pt); 00334 00335 x = 1 , y = -1, z = 0; 00336 00337 pt.x = x; 00338 pt.y = y; 00339 pt.z = z; 00340 pc.push_back (pt); 00341 00342 x = 1.5 , y = -1, z = 0.5; 00343 00344 pt.x = x; 00345 pt.y = y; 00346 pt.z = z; 00347 pc.push_back (pt); 00348 00349 00350 x = 0.8 , y = -1, z = 1.2; 00351 00352 pt.x = x; 00353 pt.y = y; 00354 pt.z = z; 00355 pc.push_back (pt); 00356 00357 x = 0.5 , y = -1, z = 1.5; 00358 pt.x = x; 00359 pt.y = y; 00360 pt.z = z; 00361 pc.push_back (pt); 00362 00363 x = 0 , y = -1, z = 1; 00364 pt.x = x; 00365 pt.y = y; 00366 pt.z = z; 00367 pc.push_back (pt); 00368 00369 x = -1 , y = -1, z = 2; 00370 pt.x = x; 00371 pt.y = y; 00372 pt.z = z; 00373 pc.push_back (pt); 00374 00375 x = 0 , y = -1, z = 0.5; 00376 pt.x = x; 00377 pt.y = y; 00378 pt.z = z; 00379 pc.push_back (pt); 00380 00381 x = -0.5 , y = -1, z = -0.5; 00382 pt.x = x; 00383 pt.y = y; 00384 pt.z = z; 00385 pc.push_back (pt); 00386 Eigen::VectorXf centroid; 00387 pcl::computeNDCentroid (pc, centroid); 00388 //std::cout << " centroid : \n" << centroid << std::endl; 00389 00390 s.centroid.x = centroid[0]; 00391 s.centroid.y = centroid[1]; 00392 s.centroid.z = centroid[2]; 00393 pcl::toROSMsg (pc, pc2); 00394 s.points.push_back (pc2); 00395 00396 } 00397 00398 void 00399 sixthShape (cob_3d_mapping_msgs::Shape& s, Eigen::Vector3f normal, Eigen::Vector3f color) 00400 { 00401 00402 pcl::PointXYZ pt; 00403 pcl::PointCloud<pcl::PointXYZ> pc; 00404 sensor_msgs::PointCloud2 pc2; 00405 00406 s.id = 5; 00407 00408 s.params[0] = normal[0]; 00409 s.params[1] = normal[1]; 00410 s.params[2] = normal[2]; 00411 s.params[3] = 0; 00412 00413 s.color.r = color[0]; 00414 s.color.g = color[1]; 00415 s.color.b = color[2]; 00416 s.color.a = 1; 00417 00418 int x = 2, y = 0, z = 0; 00419 pt.x = x; 00420 pt.y = y; 00421 pt.z = z; 00422 pc.push_back (pt); 00423 00424 x = 2, y = 1, z = 0; 00425 pt.x = x; 00426 pt.y = y; 00427 pt.z = z; 00428 pc.push_back (pt); 00429 00430 x = 2, y = 1, z = 1; 00431 pt.x = x; 00432 pt.y = y; 00433 pt.z = z; 00434 pc.push_back (pt); 00435 00436 x = 2, y = 0, z = 1; 00437 pt.x = x; 00438 pt.y = y; 00439 pt.z = z; 00440 pc.push_back (pt); 00441 00442 Eigen::VectorXf centroid; 00443 pcl::computeNDCentroid (pc, centroid); 00444 00445 s.centroid.x = centroid[0]; 00446 s.centroid.y = centroid[1]; 00447 s.centroid.z = centroid[2]; 00448 pcl::toROSMsg (pc, pc2); 00449 s.points.push_back (pc2); 00450 } 00451 00452 int 00453 main (int argc, char **argv) 00454 { 00455 00456 ros::init (argc, argv, "test_shape_array"); 00457 ros::NodeHandle n; 00458 ros::Publisher pub = n.advertise<cob_3d_mapping_msgs::ShapeArray> ("/geometry_map/map_array", 1); 00459 00460 ROS_INFO("\nPublishing shape_array..........."); 00461 ros::Rate loop_rate (1); 00462 loop_rate.sleep (); 00463 uint32_t seq = 0; 00464 00465 //while (ros::ok ()) 00466 { 00467 cob_3d_mapping_msgs::ShapeArray sa; 00468 sa.header.frame_id = "/map"; 00469 sa.header.stamp = ros::Time::now (); 00470 sa.header.seq = seq++; 00471 00472 cob_3d_mapping_msgs::Shape s; 00473 s.params.resize (4); 00474 00475 s.header.frame_id = "/map"; 00476 s.header.stamp = sa.header.stamp; 00477 00478 s.type = cob_3d_mapping_msgs::Shape::POLYGON; 00479 s.holes.push_back (false); 00480 00481 Eigen::Vector3f normal (0, 0, 1); 00482 Eigen::Vector3f color (1, 0, 0); 00483 00484 firstShape (s, normal, color); 00485 sa.shapes.push_back (s); 00486 s.points.clear (); 00487 00488 color[0] = 0; 00489 color[1] = 1; 00490 color[2] = 0; 00491 00492 secondShape (s, normal, color); 00493 sa.shapes.push_back (s); 00494 s.points.clear (); 00495 00496 color[0] = 1; 00497 color[1] = 1; 00498 color[2] = 0; 00499 00500 thirdShape (s, normal, color); 00501 sa.shapes.push_back (s); 00502 s.points.clear (); 00503 00504 normal[0] = 0.707; 00505 normal[1] = 0.707; 00506 normal[2] = 0.707; 00507 00508 color[0] = 0; 00509 color[1] = 0; 00510 color[2] = 1; 00511 00512 fourthShape (s, normal, color); 00513 sa.shapes.push_back (s); 00514 s.points.clear (); 00515 /* 00516 normal[0] = 0.866; 00517 normal[1] = 0.5; 00518 normal[2] = 0.5; 00519 */ 00520 normal[0] = 0; 00521 normal[1] = 1; 00522 normal[2] = 0; 00523 00524 color[0] = 1; 00525 color[1] = 1; 00526 color[2] = 1; 00527 fifthShape (s, normal, color); 00528 sa.shapes.push_back (s); 00529 s.points.clear (); 00530 00531 normal[0] = 1; 00532 normal[1] = 0; 00533 normal[2] = 0; 00534 00535 color[0] = 0; 00536 color[1] = 1; 00537 color[2] = 1; 00538 sixthShape (s, normal, color); 00539 sa.shapes.push_back (s); 00540 s.points.clear (); 00541 00542 pub.publish (sa); 00543 loop_rate.sleep (); 00544 ros::spin (); 00545 //loop_rate.sleep (); 00546 } 00547 00548 return 0; 00549 } 00550