00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00034 #include <stdio.h>
00035 #include <ros/ros.h>
00036 #include <visualization_msgs/Marker.h>
00037 #include <sensor_msgs/LaserScan.h>
00038 #include <sensor_msgs/PointCloud2.h>
00039 #include <tf/transform_listener.h>
00040 #include <pcl_ros/transforms.h>
00041 #include <pcl/ros/conversions.h>
00042 #include <pcl/point_cloud.h>
00043 #include <pcl/point_types.h>
00044 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00045 #include <pcl/filters/extract_indices.h>
00046 #include <pcl/filters/project_inliers.h>
00047 #include <pcl/filters/voxel_grid.h>
00048 #include <points_from_volume/points_from_volume.h>
00049 #include <trajectory_planner/coordinates.h>
00050
00051
00052 #define PFLN printf("FILE %s LINE %d\n",__FILE__, __LINE__);
00053
00054
00055 using namespace std;
00056
00057
00058 ros::NodeHandle* p_n;
00059 ros::Publisher cloud_pub, cloud_pub2, cloud_pub3, cloud_pub4, Publisher, cloud_pub5;
00060 tf::TransformListener *p_listener;
00061 pcl::PointCloud<pcl::PointXYZ> convex_hull1, convex_hull2, convex_hull3;
00062 ros::Publisher vis_pub, vis_pub2, vis_pub3, vis_pub4, car_pub;
00063 points_from_volume<pcl::PointXYZ> pfv, pfv2, pfv3, pfv4;
00064 trajectory_planner::coordinates message;
00065
00066 double spot_length=1.5;
00067 double spot_wide=0.45;
00068 double spot_high=0.6;
00069 double spot_distance=0.125;
00070 double SpotDetected=0;
00071
00077 void cloud_cb (const sensor_msgs::PointCloud2ConstPtr & pcmsg_in)
00078 {
00079
00080 pcl::PointCloud<pcl::PointXYZ> pc_in;
00081 pcl::fromROSMsg(*pcmsg_in,pc_in);
00082
00083
00084
00085 tf::StampedTransform transform;
00086 try
00087 {
00088 p_listener->lookupTransform(pcmsg_in->header.frame_id, "/vehicle_odometry", ros::Time(0), transform);
00089 }
00090 catch (tf::TransformException ex)
00091 {
00092 ROS_ERROR("%s",ex.what());
00093 }
00094
00095
00096
00097 pcl::PointCloud<pcl::PointXYZ> pc_transformed;
00098 pcl::PointCloud<pcl::PointXYZ> pc_ahead, pc_spot, pc_behind, pc_ground;
00099 pcl_ros::transformPointCloud(pc_in,pc_transformed, transform.inverse());
00100 pc_transformed.header.frame_id = "/vehicle_odometry";
00101
00102
00103
00104 pfv.convexhull_function(pc_transformed, 0.0, -0.6, false);
00105 pc_ahead=pfv.get_pc_in_volume();
00106 pc_ahead.header.frame_id = "/vehicle_odometry";
00107
00108 pfv2.convexhull_function(pc_transformed, 0.0, -0.6, false);
00109 pc_spot=pfv2.get_pc_in_volume();
00110 pc_spot.header.frame_id = "/vehicle_odometry";
00111
00112 pfv3.convexhull_function(pc_transformed, 0.0, -0.6, false);
00113 pc_behind=pfv3.get_pc_in_volume();
00114 pc_behind.header.frame_id = "/vehicle_odometry";
00115
00116 pfv4.convexhull_function(pc_transformed, 0.07, 0.0, false);
00117 pc_ground=pfv4.get_pc_in_volume();
00118 pc_ground.header.frame_id = "/vehicle_odometry";
00119
00120
00121
00122 sensor_msgs::PointCloud2 pcmsg_out;
00123 pcl::toROSMsg(pc_ahead, pcmsg_out);
00124
00125 sensor_msgs::PointCloud2 pcmsg_out2;
00126 pcl::toROSMsg(pc_spot, pcmsg_out2);
00127
00128 sensor_msgs::PointCloud2 pcmsg_out3;
00129 pcl::toROSMsg(pc_behind, pcmsg_out3);
00130
00131 sensor_msgs::PointCloud2 pcmsg_out4;
00132 pcl::toROSMsg(pc_ground, pcmsg_out4);
00133
00134
00135
00136
00137 visualization_msgs::Marker marker_car;
00138 marker_car.header.frame_id = "/vehicle_odometry";
00139 marker_car.header.stamp = ros::Time();
00140 marker_car.ns = "my_namespace";
00141 marker_car.id = 0;
00142 marker_car.type = visualization_msgs::Marker::CUBE;
00143 marker_car.action = visualization_msgs::Marker::ADD;
00144 marker_car.scale.x = 0.8;
00145 marker_car.scale.y = spot_wide;
00146 marker_car.scale.z = spot_high;
00147 marker_car.pose.position.x = 0.8/2;
00148 marker_car.pose.position.y = 0;
00149 marker_car.pose.position.z = spot_high/2;
00150 marker_car.pose.orientation.x = 0.0;
00151 marker_car.pose.orientation.y = 0.0;
00152 marker_car.pose.orientation.z = 0.0;
00153 marker_car.pose.orientation.w = 1.0;
00154 marker_car.color.a = 0.2;
00155 marker_car.color.r = 0.0;
00156 marker_car.color.g = 0.0;
00157 marker_car.color.b = 1.0;
00158
00159 int condition=0;
00160
00161 visualization_msgs::Marker marker;
00162 marker.header.frame_id = "/vehicle_odometry";
00163 marker.header.stamp = ros::Time();
00164 marker.ns = "my_namespace";
00165 marker.id = 0;
00166 marker.type = visualization_msgs::Marker::CUBE;
00167 marker.action = visualization_msgs::Marker::ADD;
00168 marker.scale.x = spot_length;
00169 marker.scale.y = spot_wide;
00170 marker.scale.z = spot_high;
00171 marker.pose.position.x = spot_length/2;
00172 marker.pose.position.y = spot_wide + spot_distance;
00173 marker.pose.position.z = spot_high/2;
00174 marker.pose.orientation.x = 0.0;
00175 marker.pose.orientation.y = 0.0;
00176 marker.pose.orientation.z = 0.0;
00177 marker.pose.orientation.w = 1.0;
00178 marker.color.a = 0.3;
00179 if(pc_ahead.points.size()<5)
00180 {
00181 marker.color.r = 0.0;
00182 marker.color.g = 1.0;
00183 marker.color.b = 0.0;
00184 condition=condition+0.5;
00185 }
00186 else
00187 {
00188 marker.color.r = 1.0;
00189 marker.color.g = 1.0;
00190 marker.color.b = 0.0;
00191 }
00192
00193
00194 visualization_msgs::Marker marker2;
00195 marker2.header.frame_id = "/vehicle_odometry";
00196 marker2.header.stamp = ros::Time();
00197 marker2.ns = "my_namespace";
00198 marker2.id = 0;
00199 marker2.type = visualization_msgs::Marker::CUBE;
00200 marker2.action = visualization_msgs::Marker::ADD;
00201 marker2.scale.x = spot_length;
00202 marker2.scale.y = spot_wide;
00203 marker2.scale.z = spot_high;
00204 marker2.pose.position.x = -spot_length/2;
00205 marker2.pose.position.y = spot_wide + spot_distance;
00206 marker2.pose.position.z = spot_high/2;
00207 marker2.pose.orientation.x = 0.0;
00208 marker2.pose.orientation.y = 0.0;
00209 marker2.pose.orientation.z = 0.0;
00210 marker2.pose.orientation.w = 1.0;
00211 marker2.color.a = 0.3;
00212 if(pc_spot.points.size()<5)
00213 {
00214 marker2.color.r = 0.0;
00215 marker2.color.g = 1.0;
00216 marker2.color.b = 0.0;
00217 condition=condition+1;
00218 }
00219 else
00220 {
00221 marker2.color.r = 1.0;
00222 marker2.color.g = 0.0;
00223 marker2.color.b = 0.0;
00224 }
00225
00226
00227 visualization_msgs::Marker marker3;
00228 marker3.header.frame_id = "/vehicle_odometry";
00229 marker3.header.stamp = ros::Time();
00230 marker3.ns = "my_namespace";
00231 marker3.id = 0;
00232 marker3.type = visualization_msgs::Marker::CUBE;
00233 marker3.action = visualization_msgs::Marker::ADD;
00234 marker3.scale.x = spot_length;
00235 marker3.scale.y = spot_wide;
00236 marker3.scale.z = spot_high;
00237 marker3.pose.position.x = -spot_length - spot_length/2;
00238 marker3.pose.position.y = spot_wide + spot_distance;
00239 marker3.pose.position.z = spot_high/2;
00240 marker3.pose.orientation.x = 0.0;
00241 marker3.pose.orientation.y = 0.0;
00242 marker3.pose.orientation.z = 0.0;
00243 marker3.pose.orientation.w = 1.0;
00244 marker3.color.a = 0.3;
00245 if(pc_behind.points.size()<5)
00246 {
00247 marker3.color.r = 1.0;
00248 marker3.color.g = 0.0;
00249 marker3.color.b = 0.0;
00250 }
00251 else
00252 {
00253 marker3.color.r = 0.0;
00254 marker3.color.g = 1.0;
00255 marker3.color.b = 0.0;
00256 condition=condition+1;
00257 }
00258
00259
00260 visualization_msgs::Marker marker4;
00261 marker4.header.frame_id = "/vehicle_odometry";
00262 marker4.header.stamp = ros::Time();
00263 marker4.ns = "my_namespace";
00264 marker4.id = 0;
00265 marker4.type = visualization_msgs::Marker::CUBE;
00266 marker4.action = visualization_msgs::Marker::ADD;
00267 marker4.scale.x = spot_length;
00268 marker4.scale.y = spot_wide;
00269 marker4.scale.z = 0.05;
00270 marker4.pose.position.x = - spot_length/2;
00271 marker4.pose.position.y = spot_wide + spot_distance;
00272 marker4.pose.position.z = -0.025;
00273 marker4.pose.orientation.x = 0.0;
00274 marker4.pose.orientation.y = 0.0;
00275 marker4.pose.orientation.z = 0.0;
00276 marker4.pose.orientation.w = 1.0;
00277 marker4.color.a = 0.6;
00278 marker4.color.r = 0.4;
00279 marker4.color.g = 0.8;
00280 marker4.color.b = 0.9;
00281 if(pc_ground.points.size()<5)
00282 {
00283 marker4.color.r = 1.0;
00284 marker4.color.g = 0.0;
00285 marker4.color.b = 0.0;
00286 }
00287 else
00288 {
00289 marker4.color.r = 0.0;
00290 marker4.color.g = 1.0;
00291 marker4.color.b = 0.0;
00292 condition=condition+1;
00293 }
00294
00295
00296
00297 car_pub.publish(marker_car);
00298 vis_pub.publish(marker);
00299 vis_pub2.publish(marker2);
00300 vis_pub3.publish(marker3);
00301 vis_pub4.publish(marker4);
00302
00303 cloud_pub.publish(pcmsg_out);
00304 cloud_pub2.publish(pcmsg_out2);
00305 cloud_pub3.publish(pcmsg_out3);
00306 cloud_pub4.publish(pcmsg_out4);
00307
00308
00309
00310 double xpos=marker2.pose.position.x;
00311 double ypos=marker2.pose.position.y;
00312 double zpos=0.0;
00313
00314 tf::StampedTransform transform2;
00315
00316 try
00317 {
00318 p_listener->lookupTransform("/vehicle_odometry", "/world", ros::Time(0), transform2);
00319 }
00320 catch (tf::TransformException ex)
00321 {
00322 ROS_ERROR("%s",ex.what());
00323
00324 }
00325
00326 pcl::PointCloud<pcl::PointXYZ> pc_spot_coordinate_in;
00327 pcl::PointCloud<pcl::PointXYZ> pc_spot_coordinate_out;
00328
00329 pcl::PointXYZ pt1;
00330 pt1.x = xpos-0.50;
00331 pt1.y= ypos+0.14;
00332 pt1.z= zpos;
00333 pc_spot_coordinate_in.points.push_back(pt1);
00334
00335 pcl_ros::transformPointCloud(pc_spot_coordinate_in,pc_spot_coordinate_out, transform2.inverse());
00336 pc_spot_coordinate_out.header.frame_id = "/world";
00337
00338 double orix;
00339 double oriy;
00340 double oriz;
00341 double oriw;
00342
00343 orix=transform2.getRotation()[0];
00344 oriy=transform2.getRotation()[1];
00345 oriz=transform2.getRotation()[2];
00346 oriw=transform2.getRotation()[3];
00347
00348 double thheta=atan2(2*(oriw*oriz+orix*oriy),1-2*(oriy*oriy+oriz*oriz));
00349
00350
00351
00352
00353
00354
00355
00356 if(condition>=3 && SpotDetected==0)
00357 {
00358
00359
00360 message.x=(pc_spot_coordinate_out.points[0].x);
00361 message.y=(pc_spot_coordinate_out.points[0].y);
00362 message.theta=-thheta;
00363
00364 printf("Parking in: %f %f \n",pc_spot_coordinate_out.points[0].x,pc_spot_coordinate_out.points[0].y);
00365
00366 sensor_msgs::PointCloud2 pcmsg_parking_place;
00367 pcl::toROSMsg(pc_spot_coordinate_out, pcmsg_parking_place);
00368 cloud_pub5.publish(pcmsg_parking_place);
00369
00370
00371
00372
00373
00374 Publisher.publish(message);
00375 SpotDetected=1;
00376
00377 }
00378 }
00379
00386 int main(int argc, char **argv)
00387 {
00388 ros::init(argc, argv, "pc_transformer_node");
00389 ros::NodeHandle n;
00390 tf::TransformListener listener(n,ros::Duration(10));
00391 p_listener=&listener;
00392 p_n=&n;
00393 Publisher = n.advertise<trajectory_planner::coordinates>("/msg_coordinates", 1000);
00394
00395
00396
00397
00398
00399 car_pub = n.advertise<visualization_msgs::Marker>( "car", 0 );
00400 vis_pub = n.advertise<visualization_msgs::Marker>( "parking_ahead", 0 );
00401 vis_pub2 = n.advertise<visualization_msgs::Marker>( "parking_spot", 0 );
00402 vis_pub3 = n.advertise<visualization_msgs::Marker>( "parking_behind", 0 );
00403 vis_pub4 = n.advertise<visualization_msgs::Marker>( "ground", 0 );
00404
00405
00406
00407
00408
00409
00410 convex_hull1.header.frame_id="/vehicle_odometry";
00411 pcl::PointXYZ pt1;
00412 pt1.x = spot_length/2 + spot_length/2; pt1.y= (spot_wide + spot_distance) + spot_wide/2; pt1.z= 0.02;
00413 convex_hull1.points.push_back(pt1);
00414 pt1.x = spot_length/2 + spot_length/2; pt1.y= (spot_wide + spot_distance) - spot_wide/2; pt1.z= 0.02;
00415 convex_hull1.points.push_back(pt1);
00416 pt1.x = spot_length/2 - spot_length/2; pt1.y= (spot_wide + spot_distance) - spot_wide/2; pt1.z= 0.02;
00417 convex_hull1.points.push_back(pt1);
00418 pt1.x = spot_length/2 - spot_length/2; pt1.y= (spot_wide + spot_distance) + spot_wide/2; pt1.z= 0.02;
00419 convex_hull1.points.push_back(pt1);
00420 pfv.set_convex_hull(convex_hull1);
00421
00422
00423 convex_hull2.header.frame_id="/vehicle_odometry";
00424 pcl::PointXYZ pt2;
00425 pt2.x = spot_length/2 - spot_length/2; pt2.y= (spot_wide + spot_distance) + spot_wide/2; pt2.z= 0.02;
00426 convex_hull2.points.push_back(pt2);
00427 pt2.x = spot_length/2 - spot_length/2; pt2.y= (spot_wide + spot_distance) - spot_wide/2; pt2.z= 0.02;
00428 convex_hull2.points.push_back(pt2);
00429 pt2.x = - spot_length; pt2.y= (spot_wide + spot_distance) - spot_wide/2; pt2.z= 0.02;
00430 convex_hull2.points.push_back(pt2);
00431 pt2.x = - spot_length; pt2.y= (spot_wide + spot_distance) + spot_wide/2; pt2.z= 0.02;
00432 convex_hull2.points.push_back(pt2);
00433 pfv2.set_convex_hull(convex_hull2);
00434
00435
00436 convex_hull3.header.frame_id="/vehicle_odometry";
00437 pcl::PointXYZ pt3;
00438 pt3.x = - spot_length; pt3.y= (spot_wide + spot_distance) + spot_wide/2; pt3.z= 0.02;
00439 convex_hull3.points.push_back(pt3);
00440 pt3.x = - spot_length; pt3.y= (spot_wide + spot_distance) - spot_wide/2; pt3.z= 0.02;
00441 convex_hull3.points.push_back(pt3);
00442 pt3.x = - spot_length - spot_length; pt3.y= (spot_wide + spot_distance) - spot_wide/2; pt3.z= 0.02;
00443 convex_hull3.points.push_back(pt3);
00444 pt3.x = - spot_length - spot_length; pt3.y= (spot_wide + spot_distance) + spot_wide/2; pt3.z= 0.02;
00445 convex_hull3.points.push_back(pt3);
00446 pfv3.set_convex_hull(convex_hull3);
00447
00448 pfv4.set_convex_hull(convex_hull2);
00449
00450
00451
00452
00453
00454
00455 cloud_pub = n.advertise<sensor_msgs::PointCloud2>("/pc_ahead", 1);
00456 cloud_pub2 = n.advertise<sensor_msgs::PointCloud2>("/pc_spot", 1);
00457 cloud_pub3 = n.advertise<sensor_msgs::PointCloud2>("/pc_behind", 1);
00458 cloud_pub4 = n.advertise<sensor_msgs::PointCloud2>("/pc_ground", 1);
00459 cloud_pub5 = n.advertise<sensor_msgs::PointCloud2>("/pc_parking_location", 1);
00460
00461
00462
00463
00464
00465
00466 ros::Subscriber sub = n.subscribe ("/pc_out_pointcloud", 1, cloud_cb);
00467
00468 ros::Rate loop_rate(30);
00469 ros::spin();
00470 }