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
00027
00028
00029
00035 #include <class_colision_time.h>
00036
00037
00038
00039 visualization_msgs::Marker mark_cluster(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster, std::string ns ,int id, float r, float g, float b);
00040
00041 visualization_msgs::Marker mark_side_cluster(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster, std::string ns ,int id, float r, float g, float b);
00042
00043 visualization_msgs::Marker generic_text(float x, float y, float z , float r, float g, float b, float scale, std::string txt, std::string frm_id, std::string ns);
00044
00045
00046 ros::Publisher points_pub;
00047
00048 ros::Publisher marker_fronts_publisher;
00049 ros::Publisher marker_front_text_publisher;
00050
00051
00052
00053 ros::Publisher marker_side_publisher;
00054 ros::Publisher marker_side_text_publisher;
00055 ros::Publisher marker_side_text_blink_publisher;
00056 ros::Publisher marker_generic_text_blink_left_publisher;
00057
00058
00059
00060
00061 tf::TransformListener *listener_center_bumper_ptr;
00062 class_colision_time::TYPE_msg_mtt obstacle_zone_front;
00063 class_colision_time::TYPE_msg_mtt obstacle_left;
00064 class_colision_time::TYPE_msg_partial partial_msg;
00065 class_colision_time::TYPE_msg_velocity velocity_msg;
00066 class_colision_time::TYPE_msg_plc plc_msg;
00067 class_colision_time::TYPE_msg_bags colision_time;
00068
00069
00077 int cria_txt(int x)
00078 {
00079 FILE *fp;
00080 string nane_file;
00081
00082 nane_file.append("../");
00083 nane_file.append(colision_time.name_file);
00084 nane_file.erase(nane_file.end()-4, nane_file.end());
00085 nane_file.append(".txt");
00086 cout<< "msg_save:"<< colision_time.name_file<<endl;
00087 fp = fopen(nane_file.c_str(),"a+");
00088
00089
00090
00091 if (fp==NULL)
00092 {
00093
00094 cout<<"cannot open file: " << nane_file.c_str() <<endl;
00095
00096 }
00097 if (x==1){
00098 fprintf(fp,"%s \t %s \t %f \t %f \t %f \n", colision_time.name_file.c_str(), colision_time.sit_type_1.c_str(),colision_time.sit_begin_1, colision_time.duration_1, colision_time.sit_end_1);
00099 cout<<"cria txt 1"<<endl;
00100 }
00101 if (x==2){
00102 fprintf(fp,"%s \t %s \t %f \t %f \t %f \n", colision_time.name_file.c_str(), colision_time.sit_type_2.c_str(),colision_time.sit_begin_2, colision_time.duration_2, colision_time.sit_end_2);
00103 cout<<"cria txt 2"<<endl;
00104 }
00105 if (x==3){
00106 fprintf(fp,"%s \t %s \t %f \t %f \t %f \n", colision_time.name_file.c_str(), colision_time.sit_type_3.c_str(),colision_time.sit_begin_3, colision_time.duration_3, colision_time.sit_end_3);
00107 cout<<"cria txt 3"<<endl;
00108 }
00109 if (x==4){
00110 fprintf(fp,"%s \t %s \t %f \t %f \t %f \n", colision_time.name_file.c_str(), colision_time.sit_type_4.c_str(),colision_time.sit_begin_4, colision_time.duration_4, colision_time.sit_end_4);
00111 cout<<"cria txt 4"<<endl;
00112 }
00113
00114
00115 fclose(fp);
00116
00117 return 0;
00118 };
00119
00120
00126 void initialization_variables(void)
00127 {
00128 colision_time.internal_1=0;
00129 colision_time.internal_2=0;
00130 colision_time.internal_3=0;
00131 colision_time.internal_4=0;
00132 }
00133
00139 void begin_situation(void)
00140 {
00141
00142
00143
00144
00145
00146 if(colision_time.sit_1==1 && colision_time.internal_1==0)
00147 {
00148
00149 colision_time.lst_obj_sit_1=ros::Time::now().toSec();
00150 colision_time.sit_begin_1=ros::Time::now().toSec();
00151 colision_time.internal_1=1;
00152 }
00153 if (colision_time.sit_1==1 && colision_time.internal_1==1)
00154 {colision_time.lst_obj_sit_1=ros::Time::now().toSec(); }
00155
00156 if(ros::Time::now().toSec()-colision_time.lst_obj_sit_1<1 )
00157 {
00158 colision_time.sit_1=1;
00159
00160 }else
00161 {
00162 if(colision_time.sit_1==0 && colision_time.internal_1==1)
00163 {
00164 colision_time.sit_type_1="object detected--> vehicle behind the car";
00165
00166 colision_time.duration_1=colision_time.bag_time-colision_time.sit_begin_1;
00167 colision_time.sit_end_1=colision_time.bag_time;
00168
00169
00170 colision_time.internal_1=0;
00171 cria_txt(1);
00172
00173 }
00174 }
00175
00176
00177 if(colision_time.sit_2==1 && colision_time.internal_2==0)
00178 {
00179
00180 colision_time.lst_obj_sit_2=ros::Time::now().toSec();
00181 colision_time.sit_begin_2=ros::Time::now().toSec();
00182 colision_time.internal_2=1;
00183 }
00184 if (colision_time.sit_2==1 && colision_time.internal_2==1)
00185 {colision_time.lst_obj_sit_2=ros::Time::now().toSec(); }
00186
00187 if(ros::Time::now().toSec()-colision_time.lst_obj_sit_2<1 )
00188 {
00189 colision_time.sit_2=1;
00190
00191 }else
00192 {
00193 if(colision_time.sit_2==0 && colision_time.internal_2==1)
00194 {
00195 colision_time.sit_type_2="object detected--> Colision Risk";
00196
00197 colision_time.duration_2=colision_time.bag_time-colision_time.sit_begin_2;
00198 colision_time.sit_end_2=colision_time.bag_time;
00199
00200
00201 colision_time.internal_2=0;
00202 cria_txt(2);
00203 cout<<"cria txt 2"<<endl;
00204 }
00205 }
00206
00207 if(colision_time.sit_3==1 && colision_time.internal_3==0)
00208 {
00209
00210 colision_time.lst_obj_sit_3=ros::Time::now().toSec();
00211 colision_time.sit_begin_3=ros::Time::now().toSec();
00212 colision_time.internal_3=1;
00213 }
00214 if (colision_time.sit_3==1 && colision_time.internal_3==1)
00215 {colision_time.lst_obj_sit_3=ros::Time::now().toSec(); }
00216
00217 if(ros::Time::now().toSec()-colision_time.lst_obj_sit_3<1 )
00218 {
00219 colision_time.sit_3=1;
00220
00221 }else
00222 {
00223 if(colision_time.sit_3==0 && colision_time.internal_3==1)
00224 {
00225 colision_time.sit_type_3="object detected--> Forgot to blink left!";
00226
00227 colision_time.duration_3=colision_time.bag_time-colision_time.sit_begin_3;
00228 colision_time.sit_end_3=colision_time.bag_time;
00229
00230
00231 colision_time.internal_3=0;
00232 cria_txt(3);
00233 cout<<"cria txt 3"<<endl;
00234 }
00235 }
00236
00237 if(colision_time.sit_4==1 && colision_time.internal_4==0)
00238 {
00239
00240 colision_time.lst_obj_sit_4=ros::Time::now().toSec();
00241 colision_time.sit_begin_4=ros::Time::now().toSec();
00242 colision_time.internal_4=1;
00243 }
00244 if (colision_time.sit_4==1 && colision_time.internal_4==1)
00245 {colision_time.lst_obj_sit_4=ros::Time::now().toSec(); }
00246
00247 if(ros::Time::now().toSec()-colision_time.lst_obj_sit_4<1 )
00248 {
00249 colision_time.sit_4=1;
00250
00251 }else
00252 {
00253 if(colision_time.sit_4==0 && colision_time.internal_4==1)
00254 {
00255 colision_time.sit_type_4="object detected--> Forgot to blink right";
00256
00257 colision_time.duration_4=colision_time.bag_time-colision_time.sit_begin_4;
00258 colision_time.sit_end_4=colision_time.bag_time;
00259
00260
00261 colision_time.internal_4=0;
00262 cria_txt(4);
00263 cout<<"cria txt 4 "<<endl;
00264 }
00265 }
00266
00267 };
00268
00269
00275 void topic_callback_partial(atlascar_base::AtlascarPartialStatus AtlascarPartialStatus_msg)
00276 {
00277 partial_msg.lights_high=AtlascarPartialStatus_msg.lights_high;
00278 partial_msg.lights_medium=AtlascarPartialStatus_msg.lights_medium;
00279 partial_msg.ignition=AtlascarPartialStatus_msg.ignition;
00280 partial_msg.lights_left=AtlascarPartialStatus_msg.lights_left;
00281 partial_msg.lights_right=AtlascarPartialStatus_msg.lights_right;
00282 partial_msg.danger_lights=AtlascarPartialStatus_msg.danger_lights;
00283 partial_msg.horn=AtlascarPartialStatus_msg.horn;
00284 partial_msg.throttle=AtlascarPartialStatus_msg.throttle;
00285 partial_msg.brake=AtlascarPartialStatus_msg.brake;
00286 partial_msg.clutch=AtlascarPartialStatus_msg.clutch;
00287 };
00288
00289
00295 void topic_callback_velocity(atlascar_base::AtlascarVelocityStatus AtlascarVelocityStatus_msg)
00296 {
00297 velocity_msg.counting=AtlascarVelocityStatus_msg.counting;
00298 velocity_msg.pulses_sec=AtlascarVelocityStatus_msg.pulses_sec;
00299 velocity_msg.revolutions_sec=AtlascarVelocityStatus_msg.revolutions_sec;
00300 velocity_msg.velocity=AtlascarVelocityStatus_msg.velocity;
00301 };
00307 void topic_callback_plc_status(atlascar_base::AtlascarStatus AtlascarStatus_msg)
00308 {
00309 plc_msg.steering_wheel=AtlascarStatus_msg.steering_wheel;
00310 plc_msg.rpm=AtlascarStatus_msg.rpm;
00311 cout<<plc_msg <<endl;
00312 };
00313
00319 void topic_callback_rosout_cool(rosgraph_msgs::Log rosout_msg)
00320 {
00321
00322 if (rosout_msg.msg[0]=='O' && rosout_msg.msg[1]=='p'&& rosout_msg.msg[2]=='e'&& rosout_msg.msg[6]=='g')
00323 {
00324 char name_file[1024];
00325 sscanf(rosout_msg.msg.c_str(),"%*s %s",name_file);
00326 colision_time.name_file= name_file;
00327
00328
00329
00330 }
00331 };
00332
00333
00344 void topic_callback(const mtt::TargetListPC::Ptr& msg)
00345 {
00346 colision_time.bag_time=ros::Time::now().toSec();
00347 colision_time.sit_1=0;
00348 colision_time.sit_2=0;
00349 colision_time.sit_3=0;
00350 colision_time.sit_4=0;
00351
00352
00353
00354
00355 PointCloud<PointXYZ> velocity;
00356 PointCloud<PointXYZ> velocity_1;
00357 PointCloud<PointXYZ> position_1;
00358 PointCloud<PointXYZ> position;
00359
00360 fromROSMsg(msg->velocity,velocity_1);
00361 fromROSMsg(msg->position,position_1);
00362
00363 tf::StampedTransform transform;
00364 try
00365 {
00366 listener_center_bumper_ptr->lookupTransform("/atc/vehicle/center_bumper", msg->header.frame_id, ros::Time(0), transform);
00367 }
00368 catch (tf::TransformException ex)
00369 {
00370 ROS_ERROR("%s",ex.what());
00371 }
00372
00373 pcl_ros::transformPointCloud (position_1,position,transform);
00374 pcl_ros::transformPointCloud (velocity_1,velocity,transform);
00375 position.header.frame_id="/atc/vehicle/center_bumper";
00376 velocity.header.frame_id="/atc/vehicle/center_bumper";
00377
00378 PointCloud<PointXYZ>::Ptr front_zone (new PointCloud<PointXYZ> ());
00379 front_zone->header.frame_id="/atc/vehicle/center_bumper";
00380
00381
00382 PointCloud<PointXYZ>::Ptr left_zone (new PointCloud<PointXYZ> ());
00383 left_zone->header.frame_id="/atc/vehicle/center_bumper";
00384
00385
00386 PointXYZ point;
00387
00388 for (int i=0; i<(int)position.size(); ++i)
00389 {
00390 point=position.points[i];
00391
00392 if (point.x>0 && point.x<40 && point.y>-1 && point.y<1)
00393 {
00394 front_zone->points.push_back(point);
00395 obstacle_zone_front.id=msg->id[i];
00396 obstacle_zone_front.x=point.x;
00397 obstacle_zone_front.y=point.y;
00398 obstacle_zone_front.z=point.z;
00399 obstacle_zone_front.v_x=velocity[i].x;
00400 obstacle_zone_front.v_y=velocity[i].y;
00401 obstacle_zone_front.v_z=velocity[i].z;
00402 }
00403
00404 if (point.x>-40 && point.x<-0.5 && point.y>1.2 && point.y<3.5)
00405 {
00406 left_zone->points.push_back(point);
00407 obstacle_left.id=msg->id[i];
00408 obstacle_left.x=point.x;
00409 obstacle_left.y=point.y;
00410 obstacle_left.z=point.z;
00411 obstacle_left.v_x=velocity[i].x;
00412 obstacle_left.v_y=velocity[i].y;
00413 obstacle_left.v_z=velocity[i].z;
00414 }
00415
00416 }
00417
00418 sensor_msgs::PointCloud2 ptc_front;
00419 toROSMsg(*front_zone,ptc_front);
00420 ptc_front.header.frame_id="/atc/vehicle/center_bumper";
00421 points_pub.publish(ptc_front);
00422
00423
00424 sensor_msgs::PointCloud2 ptc_side;
00425 toROSMsg(*left_zone,ptc_side);
00426 ptc_side.header.frame_id="/atc/vehicle/center_bumper";
00427 points_pub.publish(ptc_side);
00428
00429
00430
00434
00435
00436 visualization_msgs::Marker marker_front=mark_cluster(front_zone, "front_cube" ,0, 0, 0, 1);
00437 marker_fronts_publisher.publish(marker_front);
00438
00439
00440
00441 float velocity_car_front;
00442 float time_car_front;
00443 velocity_car_front=obstacle_zone_front.v_x+velocity_msg.velocity;
00444 time_car_front=obstacle_zone_front.x/obstacle_zone_front.v_x;
00445
00446 cout<<"V Atlascar ->"<< velocity_msg.velocity<<endl;
00447 cout<<"V objecto->"<< obstacle_zone_front.v_x<< endl;
00448 cout<<"V total ->"<< velocity_car_front <<endl;
00449 cout<<"eime total ->"<<time_car_front <<endl;
00450
00451 if(time_car_front>-4 && time_car_front< 0)
00452 {
00453 colision_time.sit_2=1;
00454 string msg_text="Colision Risk!!";
00455 visualization_msgs::Marker marker_front_text_front=generic_text( obstacle_zone_front.x , obstacle_zone_front.y, obstacle_zone_front.z , 1, 0, 0, 1, msg_text , "/atc/vehicle/center_bumper", "front_warning");
00456
00457 marker_front_text_publisher.publish(marker_front_text_front);
00458
00459
00460
00461
00462 }
00463
00464
00465
00469
00470
00471
00472 visualization_msgs::Marker marker_side=mark_side_cluster(left_zone, "side_cube" ,0, 0, 0, 1);
00473 marker_side_publisher.publish(marker_side);
00474
00475
00479
00480
00481
00482 long int exist_points_side=left_zone->points.size();
00483 if(exist_points_side>0)
00484 {
00485 colision_time.sit_1=1;
00486
00487 string msg_text_side="OBJECT DETECTED";
00488 visualization_msgs::Marker marker_side_text =generic_text( 0 , obstacle_left.y, 2 , 0, 0, 0.487, 1, msg_text_side ,"/atc/vehicle/center_bumper","cannot_pass");
00489
00490 marker_side_text_publisher.publish(marker_side_text);
00491 }
00492
00496
00497 if( partial_msg.lights_left==0 && plc_msg.steering_wheel<(-0.315) )
00498 {
00499 colision_time.sit_3=1;
00500 string msg_blink_side="Forgot to blink left!";
00501
00502 visualization_msgs::Marker marker_side_text_left_blink= generic_text( 3 , 6, 2 , 0, 0, 1, 1, msg_blink_side ,"/atc/vehicle/center_bumper","Blink_left");
00503
00504 marker_generic_text_blink_left_publisher.publish(marker_side_text_left_blink);
00505
00506 }
00507
00511
00512
00513 if( partial_msg.lights_right==0 && plc_msg.steering_wheel>(-0.275) && plc_msg.steering_wheel!=0 )
00514 {
00515 colision_time.sit_4=1;
00516 string msg_blink_side="Forgot to blink right!";
00517
00518 visualization_msgs::Marker marker_side_text_right_blink= generic_text(3 , -6, 2 , 0, 0, 1, 1, msg_blink_side ,"/atc/vehicle/center_bumper","Blink_right");
00519
00520 marker_side_text_blink_publisher.publish(marker_side_text_right_blink);
00521 }
00522
00523 begin_situation();
00524
00525
00526
00527 obstacle_zone_front.v_x =0;
00528 };
00529
00530
00531
00537 int main (int argc, char **argv)
00538 {
00539 ROS_INFO("Starting colision time node.");
00540
00541 ros::init(argc,argv,"colision_time");
00542 ros::NodeHandle n;
00543
00544 initialization_variables();
00545
00546
00547
00548 tf::TransformListener listener_center_bumper;
00549 listener_center_bumper_ptr=&listener_center_bumper;
00550
00551
00552 ros::Subscriber sub = n.subscribe("/mtt/trck/targets", 1, topic_callback);
00553
00554
00555
00556 ros::Subscriber sub_rosout =n.subscribe("/rosout_agg", 1, topic_callback_rosout_cool);
00557
00558
00559
00560 ros::Subscriber sub_status_plc = n.subscribe("/vhc/plc/status", 1, topic_callback_plc_status);
00561 ros::Subscriber sub_partial_status = n.subscribe("/vhc/driver/status", 1, topic_callback_partial);
00562 ros::Subscriber sub_velocity_status = n.subscribe("/vhc/velocity/status", 1, topic_callback_velocity);
00563
00564
00565
00566
00567 points_pub = n.advertise<sensor_msgs::PointCloud2>("/atc/monitoring/danger_zone", 1);
00568
00569
00570 marker_fronts_publisher= n.advertise<visualization_msgs::Marker>("/prcp/front_mrk", 1000);
00571
00572
00573 marker_side_publisher= n.advertise<visualization_msgs::Marker>("/prcp/side_mrk", 1000);
00574
00575
00576 marker_front_text_publisher= n.advertise<visualization_msgs::Marker>("/prcp/front_text_mrk", 1000);
00577
00578
00579 marker_side_text_publisher= n.advertise<visualization_msgs::Marker>("/prcp/side_text_mrk", 1000);
00580
00581
00582
00583 marker_side_text_blink_publisher= n.advertise<visualization_msgs::Marker>("/prcp/side_text_blink_right_mrk", 1000);
00584
00585
00586 marker_generic_text_blink_left_publisher= n.advertise<visualization_msgs::Marker>("/prcp/side_text_blink_left_mrk", 1000);
00587
00588
00589
00590 ros::spin();
00591
00592 return 1;
00593 }
00594
00595
00596
00611 visualization_msgs::Marker generic_text(float x, float y, float z , float r,
00612 float g, float b, float scale, std::string txt, std::string frm_id, std::string
00613 ns)
00614 {
00615 uint32_t shape = visualization_msgs::Marker::TEXT_VIEW_FACING;
00616 visualization_msgs::Marker marker_front;
00617
00618 marker_front.header.frame_id = frm_id;
00619 marker_front.header.stamp = ros::Time::now();
00620
00621
00622 marker_front.ns = ns;
00623 marker_front.id = 0;
00624 marker_front.type = shape;
00625 marker_front.action = visualization_msgs::Marker::ADD;
00626
00627 marker_front.pose.position.x = x;
00628 marker_front.pose.position.y = y;
00629 marker_front.pose.position.z = z;
00630 marker_front.scale.z = scale;
00631
00632
00633
00634
00635 marker_front.text=txt;
00636
00637 marker_front.color.r = r;
00638 marker_front.color.g = g;
00639 marker_front.color.b = b;
00640 marker_front.color.a = 0.8;
00641
00642 marker_front.lifetime = ros::Duration(0.4);
00643 return marker_front;
00644 }
00645
00646
00647
00648
00649
00650
00661 visualization_msgs::Marker mark_cluster(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster, std::string ns ,int id, float r, float g, float b)
00662 {
00663 Eigen::Vector4f centroid;
00664 Eigen::Vector4f min;
00665 Eigen::Vector4f max;
00666
00667 pcl::compute3DCentroid (*cloud_cluster, centroid);
00668 pcl::getMinMax3D (*cloud_cluster, min, max);
00669
00670 uint32_t shape = visualization_msgs::Marker::CUBE;
00671 visualization_msgs::Marker marker_front;
00672 marker_front.header.frame_id = cloud_cluster->header.frame_id;
00673 marker_front.header.stamp = ros::Time::now();
00674
00675 marker_front.ns = ns;
00676 marker_front.id = id;
00677 marker_front.type = shape;
00678 marker_front.action = visualization_msgs::Marker::ADD;
00679
00680
00681
00682 marker_front.pose.position.x = min[0];
00683 marker_front.pose.position.y = centroid[1];
00684 marker_front.pose.position.z = centroid[2];
00685 marker_front.pose.orientation.x = 0.0;
00686 marker_front.pose.orientation.y = 0.0;
00687 marker_front.pose.orientation.z = 0.0;
00688 marker_front.pose.orientation.w = 1.0;
00689
00690 marker_front.scale.x = 1;
00691 marker_front.scale.y = 1;
00692 marker_front.scale.z = 1;
00693
00694 marker_front.color.r = r;
00695 marker_front.color.g = g;
00696 marker_front.color.b = b;
00697 marker_front.color.a = 0.5;
00698
00699
00700 marker_front.lifetime = ros::Duration(0.3);
00701 return marker_front;
00702 }
00703
00704
00705
00706
00707
00718 visualization_msgs::Marker mark_side_cluster(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster, std::string ns ,int id, float r, float g, float b)
00719 {
00720 Eigen::Vector4f centroid;
00721 Eigen::Vector4f min;
00722 Eigen::Vector4f max;
00723
00724 pcl::compute3DCentroid (*cloud_cluster, centroid);
00725 pcl::getMinMax3D (*cloud_cluster, min, max);
00726
00727 uint32_t shape = visualization_msgs::Marker::CUBE;
00728 visualization_msgs::Marker marker_side;
00729 marker_side.header.frame_id = cloud_cluster->header.frame_id;
00730 marker_side.header.stamp = ros::Time::now();
00731
00732 marker_side.ns = ns;
00733 marker_side.id = id;
00734 marker_side.type = shape;
00735 marker_side.action = visualization_msgs::Marker::ADD;
00736
00737
00738
00739 marker_side.pose.position.x = max[0];
00740 marker_side.pose.position.y = centroid[1];
00741 marker_side.pose.position.z = centroid[2];
00742 marker_side.pose.orientation.x = 0.0;
00743 marker_side.pose.orientation.y = 0.0;
00744 marker_side.pose.orientation.z = 0.0;
00745 marker_side.pose.orientation.w = 1.0;
00746
00747 marker_side.scale.x = 1;
00748 marker_side.scale.y = 1;
00749 marker_side.scale.z = 1;
00750
00751 marker_side.color.r = r;
00752 marker_side.color.g = g;
00753 marker_side.color.b = b;
00754 marker_side.color.a = 1;
00755
00756
00757 marker_side.lifetime = ros::Duration(0.3);
00758 return marker_side;
00759 }
00760