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 <driver_recognition/class_recognition.h>
00035
00036
00037
00038 class_recognition::TYPE_msg_partial partial_msg;
00039
00040 class_recognition::TYPE_msg_bags recognition;
00041 FILE *fp;
00042
00048 int cria_txt(void)
00049 {
00050
00051 string nane_file;
00052
00053 nane_file.append("../");
00054 nane_file.append(recognition.name_file);
00055 nane_file.erase(nane_file.end()-4, nane_file.end());
00056 nane_file.append(".txt");
00057
00058 fp = fopen(nane_file.c_str(),"a+");
00059
00060
00061 if (fp==NULL)
00062 {
00063 cout<<"cannot open file: recognition_data.txt" <<endl;
00064 return 1;
00065 }
00066
00067 fprintf(fp,"%s \t %f \t %d \t %d \t %d \t %d \t %d \t %d \t %f \t %f \t %f\n",
00068 recognition.name_file.c_str(),
00069 recognition.bag_time,
00070 partial_msg.ignition,
00071 partial_msg.lights_left,
00072 partial_msg.lights_right,
00073 partial_msg.throttle,
00074 partial_msg.brake,
00075 partial_msg.clutch,
00076 partial_msg.velocity,
00077 partial_msg.steering_wheel,
00078 partial_msg.rpm);
00079
00080
00081
00082 fclose(fp);
00083
00084 return 0;
00085 };
00086
00087
00088
00089
00095 void topic_callback_partial(atlascar_base::AtlascarPartialStatus AtlascarPartialStatus_msg)
00096 {
00097 partial_msg.lights_high=AtlascarPartialStatus_msg.lights_high;
00098 partial_msg.lights_medium=AtlascarPartialStatus_msg.lights_medium;
00099 partial_msg.ignition=AtlascarPartialStatus_msg.ignition;
00100 partial_msg.lights_left=AtlascarPartialStatus_msg.lights_left;
00101 partial_msg.lights_right=AtlascarPartialStatus_msg.lights_right;
00102 partial_msg.danger_lights=AtlascarPartialStatus_msg.danger_lights;
00103 partial_msg.horn=AtlascarPartialStatus_msg.horn;
00104 partial_msg.throttle=AtlascarPartialStatus_msg.throttle;
00105 partial_msg.brake=AtlascarPartialStatus_msg.brake;
00106 partial_msg.clutch=AtlascarPartialStatus_msg.clutch;
00107 recognition.bag_time=ros::Time::now().toSec();
00108 };
00115 void topic_callback_velocity(atlascar_base::AtlascarVelocityStatus AtlascarVelocityStatus_msg)
00116 {
00117 partial_msg.velocity=AtlascarVelocityStatus_msg.velocity;
00118
00119
00120 cria_txt();
00121 };
00127 void topic_callback_plc_status(atlascar_base::AtlascarStatus AtlascarStatus_msg)
00128 {
00129 partial_msg.steering_wheel=AtlascarStatus_msg.steering_wheel;
00130 partial_msg.rpm=AtlascarStatus_msg.rpm;
00131
00132
00133 };
00134
00135
00141 void topic_callback_rosout(rosgraph_msgs::Log rosout_msg)
00142 {
00143
00144 if (rosout_msg.msg[0]=='O' && rosout_msg.msg[1]=='p'&& rosout_msg.msg[2]=='e'&& rosout_msg.msg[6]=='g')
00145 {
00146 char name_file[1024];
00147
00148 string names;
00149
00150 sscanf(rosout_msg.msg.c_str(),"%*s %s",name_file);
00151
00152
00153 recognition.name_file=name_file;
00154
00155
00156 }
00157 };
00158
00164 void create_head_of_file(void)
00165 {
00166
00167 fp = fopen("../recognition_data.txt","a+");
00168
00169 fprintf(fp,"%s \t %s \t %s \t %s \t %s \t %s \t %s \t %s \t %s \t %s \t %s\n",
00170 "name of file" ,
00171 "bag time",
00172 "ignition",
00173 "lights_left",
00174 "lights_right",
00175 "throttle",
00176 "brake",
00177 "clutch",
00178 "velocity",
00179 "steering_wheel",
00180 "rpm");
00181 fclose(fp);
00182 }
00183
00184
00190 int main (int argc, char **argv)
00191 {
00192 ROS_INFO("Starting recognition_data node.");
00193
00194 create_head_of_file();
00195
00196 ros::init(argc,argv,"recognition");
00197 ros::NodeHandle n;
00198
00199
00200 ros::Subscriber sub_status_plc = n.subscribe("/vhc/plc/status", 1, topic_callback_plc_status);
00201 ros::Subscriber sub_partial_status = n.subscribe("/vhc/driver/status", 1, topic_callback_partial);
00202 ros::Subscriber sub_velocity_status = n.subscribe("/vhc/velocity/status", 1, topic_callback_velocity);
00203 ros::Subscriber sub_rosout =n.subscribe("/rosout_agg", 1, topic_callback_rosout);
00204
00205
00206
00207
00208
00209 ros::spin();
00210
00211 return 1;
00212 }