Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 #include "stdr_parser/stdr_parser_yaml_file_writer.h"
00023 
00024 namespace stdr_parser
00025 {
00026   
00031   YamlFileWriter::YamlFileWriter(void)
00032   {
00033 
00034   }
00035   
00038   template void YamlFileWriter::messageToFile
00039     (stdr_msgs::Noise msg,std::string file_name);
00040   
00042   template <>
00043   YAML::Emitter& operator << <stdr_msgs::Noise>
00044     (YAML::Emitter& out, const stdr_msgs::Noise& msg)
00045   {
00046     out << YAML::BeginMap;
00047       out << YAML::Key << "noise";
00048       out << YAML::Value;
00049       out << YAML::BeginMap;
00050         out << YAML::Key << "noise_specifications";
00051         out << YAML::Value;
00052         out << YAML::BeginMap;
00053           out << YAML::Key << "noise_mean" << YAML::Value << msg.noiseMean;
00054           out << YAML::Key << "noise_std" << YAML::Value << msg.noiseStd;
00055         out << YAML::EndMap;
00056       out << YAML::EndMap;
00057     out << YAML::EndMap;
00058     return out;
00059   }
00060   
00063   template void YamlFileWriter::messageToFile
00064     (stdr_msgs::FootprintMsg msg,std::string file_name);
00065   
00067   template <>
00068   YAML::Emitter& operator << <stdr_msgs::FootprintMsg>
00069     (YAML::Emitter& out, const stdr_msgs::FootprintMsg& msg)
00070   {
00071     out << YAML::BeginMap;
00072       out << YAML::Key << "footprint";
00073       out << YAML::Value;
00074       out << YAML::BeginMap;
00075         out << YAML::Key << "footprint_specifications";
00076         out << YAML::Value;
00077         out << YAML::BeginMap;
00078           out << YAML::Key << "radius" << YAML::Value << msg.radius;
00079           out << YAML::Key << "points";
00080           out << YAML::Value;
00081           out << YAML::BeginSeq;
00082             for(unsigned int i = 0 ; i < msg.points.size() ; i++)
00083             {
00084               out << YAML::BeginMap;
00085                 out << YAML::Key << "point";
00086                 out << YAML::Value;
00087                 out << YAML::BeginMap;
00088                   out << YAML::Key << "x" << YAML::Value << msg.points[i].x;
00089                   out << YAML::Key << "y" << YAML::Value << msg.points[i].y;
00090                 out << YAML::EndMap;
00091               out << YAML::EndMap;
00092             }
00093           out << YAML::EndSeq;
00094         out << YAML::EndMap;
00095       out << YAML::EndMap;
00096     out << YAML::EndMap;
00097     return out;
00098   }
00099   
00102   template void YamlFileWriter::messageToFile
00103     (geometry_msgs::Pose2D msg,std::string file_name);
00104   
00106   template <>
00107   YAML::Emitter& operator << <geometry_msgs::Pose2D>
00108     (YAML::Emitter& out, const geometry_msgs::Pose2D& msg)
00109   {
00110     out << YAML::BeginMap;
00111       out << YAML::Key << "pose";
00112       out << YAML::Value;
00113       out << YAML::BeginMap;
00114         out << YAML::Key << "x" << YAML::Value << msg.x;
00115         out << YAML::Key << "y" << YAML::Value << msg.y;
00116         out << YAML::Key << "theta" << YAML::Value << msg.theta;
00117       out << YAML::EndMap;
00118     out << YAML::EndMap;
00119     return out;
00120   }
00121  
00124   template void YamlFileWriter::messageToFile
00125     (stdr_msgs::KinematicMsg msg,std::string file_name);
00126   
00128   template <>
00129   YAML::Emitter& operator << <stdr_msgs::KinematicMsg>
00130     (YAML::Emitter& out, const stdr_msgs::KinematicMsg& msg)
00131   {
00132     out << YAML::BeginMap;
00133       out << YAML::Key << "kinematic";
00134       out << YAML::Value;
00135       out << YAML::BeginMap;
00136         out << YAML::Key << "kinematic_specifications";
00137         out << YAML::Value;
00138         out << YAML::BeginMap;
00139           out << YAML::Key << "kinematic_type" << YAML::Value << msg.type;
00140           out << YAML::Key << "kinematic_parameters";
00141           out << YAML::Value;
00142           out << YAML::BeginMap;
00143            out << YAML::Key << "a_ux_ux" << YAML::Value << msg.a_ux_ux;
00144            out << YAML::Key << "a_ux_uy" << YAML::Value << msg.a_ux_uy;
00145            out << YAML::Key << "a_ux_w" << YAML::Value << msg.a_ux_w;
00146            out << YAML::Key << "a_uy_ux" << YAML::Value << msg.a_uy_ux;
00147            out << YAML::Key << "a_uy_uy" << YAML::Value << msg.a_uy_uy;
00148            out << YAML::Key << "a_uy_w" << YAML::Value << msg.a_uy_w;
00149            out << YAML::Key << "a_w_ux" << YAML::Value << msg.a_w_ux;
00150            out << YAML::Key << "a_w_uy" << YAML::Value << msg.a_w_uy;
00151            out << YAML::Key << "a_w_w" << YAML::Value << msg.a_w_w;
00152            out << YAML::Key << "a_g_ux" << YAML::Value << msg.a_g_ux;
00153            out << YAML::Key << "a_g_uy" << YAML::Value << msg.a_g_uy;
00154            out << YAML::Key << "a_g_w" << YAML::Value << msg.a_g_w;
00155           out << YAML::EndMap;
00156         out << YAML::EndMap;
00157       out << YAML::EndMap;
00158     out << YAML::EndMap;
00159     return out;
00160   }
00161 
00162 
00165   template void YamlFileWriter::messageToFile
00166     (stdr_msgs::LaserSensorMsg msg,std::string file_name);
00167   
00169   template <>
00170   YAML::Emitter& operator << <stdr_msgs::LaserSensorMsg>
00171     (YAML::Emitter& out, const stdr_msgs::LaserSensorMsg& msg)
00172   {
00173     out << YAML::BeginMap;
00174       out << YAML::Key << "laser";
00175       out << YAML::Value;
00176       out << YAML::BeginMap;
00177         out << YAML::Key << "laser_specifications";
00178         out << YAML::Value;
00179         out << YAML::BeginMap;
00180           out << YAML::Key << "max_angle" << YAML::Value << msg.maxAngle;
00181           out << YAML::Key << "min_angle" << YAML::Value << msg.minAngle;
00182           out << YAML::Key << "max_range" << YAML::Value << msg.maxRange;
00183           out << YAML::Key << "min_range" << YAML::Value << msg.minRange;
00184           out << YAML::Key << "num_rays" << YAML::Value << msg.numRays;
00185           out << YAML::Key << "frequency" << YAML::Value << msg.frequency;
00186           out << YAML::Key << "frame_id" << YAML::Value << msg.frame_id;
00187           out << YAML::Key << "pose";
00188           out << YAML::Value;
00189           out << YAML::BeginMap;
00190             out << YAML::Key << "x" << YAML::Value << msg.pose.x;
00191             out << YAML::Key << "y" << YAML::Value << msg.pose.y;
00192             out << YAML::Key << "theta" << YAML::Value << msg.pose.theta;
00193           out << YAML::EndMap;
00194           out << YAML::Key << "noise";
00195           out << YAML::Value;
00196           out << YAML::BeginMap;
00197             out << YAML::Key << "noise_specifications";
00198             out << YAML::Value;
00199             out << YAML::BeginMap;
00200               out << YAML::Key << "noise_mean";
00201               out << YAML::Value << msg.noise.noiseMean;
00202               out << YAML::Key << "noise_std";
00203               out << YAML::Value << msg.noise.noiseStd;
00204             out << YAML::EndMap;
00205           out << YAML::EndMap;
00206         out << YAML::EndMap;
00207       out << YAML::EndMap;
00208     out << YAML::EndMap;
00209     return out;
00210   }
00211   
00214   template void YamlFileWriter::messageToFile
00215     (stdr_msgs::SonarSensorMsg msg,std::string file_name);
00216   
00218   template <>
00219   YAML::Emitter& operator << <stdr_msgs::SonarSensorMsg>
00220     (YAML::Emitter& out, const stdr_msgs::SonarSensorMsg& msg)
00221   {
00222     out << YAML::BeginMap;
00223       out << YAML::Key << "sonar";
00224       out << YAML::Value;
00225       out << YAML::BeginMap;
00226         out << YAML::Key << "sonar_specifications";
00227         out << YAML::Value;
00228         out << YAML::BeginMap;
00229           out << YAML::Key << "cone_angle" << YAML::Value << msg.coneAngle;
00230           out << YAML::Key << "max_range" << YAML::Value << msg.maxRange;
00231           out << YAML::Key << "min_range" << YAML::Value << msg.minRange;
00232           out << YAML::Key << "frequency" << YAML::Value << msg.frequency;
00233           out << YAML::Key << "frame_id" << YAML::Value << msg.frame_id;
00234           out << YAML::Key << "pose";
00235           out << YAML::Value;
00236           out << YAML::BeginMap;
00237             out << YAML::Key << "x" << YAML::Value << msg.pose.x;
00238             out << YAML::Key << "y" << YAML::Value << msg.pose.y;
00239             out << YAML::Key << "theta" << YAML::Value << msg.pose.theta;
00240           out << YAML::EndMap;
00241           out << YAML::Key << "noise";
00242           out << YAML::Value;
00243           out << YAML::BeginMap;
00244             out << YAML::Key << "noise_specifications";
00245             out << YAML::Value;
00246             out << YAML::BeginMap;
00247               out << YAML::Key << "noise_mean";
00248               out << YAML::Value << msg.noise.noiseMean;
00249               out << YAML::Key << "noise_std";
00250               out << YAML::Value << msg.noise.noiseStd;
00251             out << YAML::EndMap;
00252           out << YAML::EndMap;
00253         out << YAML::EndMap;
00254       out << YAML::EndMap;
00255     out << YAML::EndMap;
00256     return out;
00257   }
00260   template void YamlFileWriter::messageToFile
00261     (stdr_msgs::RfidSensorMsg msg,std::string file_name);
00262   
00264   template <>
00265   YAML::Emitter& operator << <stdr_msgs::RfidSensorMsg>
00266     (YAML::Emitter& out, const stdr_msgs::RfidSensorMsg& msg)
00267   {
00268     out << YAML::BeginMap;
00269       out << YAML::Key << "rfid_reader";
00270       out << YAML::Value;
00271       out << YAML::BeginMap;
00272         out << YAML::Key << "rfid_reader_specifications";
00273         out << YAML::Value;
00274         out << YAML::BeginMap;
00275           out << YAML::Key << "angle_span" << YAML::Value << msg.angleSpan;
00276           out << YAML::Key << "max_range" << YAML::Value << msg.maxRange;
00277           out << YAML::Key << "signal_cutoff" << YAML::Value << msg.signalCutoff;
00278           out << YAML::Key << "frequency" << YAML::Value << msg.frequency;
00279           out << YAML::Key << "frame_id" << YAML::Value << msg.frame_id;
00280           out << YAML::Key << "pose";
00281           out << YAML::Value;
00282           out << YAML::BeginMap;
00283             out << YAML::Key << "x" << YAML::Value << msg.pose.x;
00284             out << YAML::Key << "y" << YAML::Value << msg.pose.y;
00285             out << YAML::Key << "theta" << YAML::Value << msg.pose.theta;
00286           out << YAML::EndMap;
00287         out << YAML::EndMap;
00288       out << YAML::EndMap;
00289     out << YAML::EndMap;
00290     return out;
00291   }
00294   template void YamlFileWriter::messageToFile
00295     (stdr_msgs::CO2SensorMsg msg,std::string file_name);
00296   
00298   template <>
00299   YAML::Emitter& operator << <stdr_msgs::CO2SensorMsg>
00300     (YAML::Emitter& out, const stdr_msgs::CO2SensorMsg& msg)
00301   {
00302     out << YAML::BeginMap;
00303       out << YAML::Key << "co2_sensor";
00304       out << YAML::Value;
00305       out << YAML::BeginMap;
00306         out << YAML::Key << "co2_sensor_specifications";
00307         out << YAML::Value;
00308         out << YAML::BeginMap;
00309           
00310           out << YAML::Key << "max_range" << YAML::Value << msg.maxRange;
00311           
00312           out << YAML::Key << "frequency" << YAML::Value << msg.frequency;
00313           out << YAML::Key << "frame_id" << YAML::Value << msg.frame_id;
00314           out << YAML::Key << "pose";
00315           out << YAML::Value;
00316           out << YAML::BeginMap;
00317             out << YAML::Key << "x" << YAML::Value << msg.pose.x;
00318             out << YAML::Key << "y" << YAML::Value << msg.pose.y;
00319             out << YAML::Key << "theta" << YAML::Value << msg.pose.theta;
00320           out << YAML::EndMap;
00321         out << YAML::EndMap;
00322       out << YAML::EndMap;
00323     out << YAML::EndMap;
00324     return out;
00325   }
00328   template void YamlFileWriter::messageToFile
00329     (stdr_msgs::ThermalSensorMsg msg,std::string file_name);
00330   
00332   template <>
00333   YAML::Emitter& operator << <stdr_msgs::ThermalSensorMsg>
00334     (YAML::Emitter& out, const stdr_msgs::ThermalSensorMsg& msg)
00335   {
00336     out << YAML::BeginMap;
00337       out << YAML::Key << "thermal_sensor";
00338       out << YAML::Value;
00339       out << YAML::BeginMap;
00340         out << YAML::Key << "thermal_sensor_specifications";
00341         out << YAML::Value;
00342         out << YAML::BeginMap;
00343           out << YAML::Key << "angle_span" << YAML::Value << msg.angleSpan;
00344           out << YAML::Key << "max_range" << YAML::Value << msg.maxRange;
00345           out << YAML::Key << "frequency" << YAML::Value << msg.frequency;
00346           out << YAML::Key << "frame_id" << YAML::Value << msg.frame_id;
00347           out << YAML::Key << "pose";
00348           out << YAML::Value;
00349           out << YAML::BeginMap;
00350             out << YAML::Key << "x" << YAML::Value << msg.pose.x;
00351             out << YAML::Key << "y" << YAML::Value << msg.pose.y;
00352             out << YAML::Key << "theta" << YAML::Value << msg.pose.theta;
00353           out << YAML::EndMap;
00354         out << YAML::EndMap;
00355       out << YAML::EndMap;
00356     out << YAML::EndMap;
00357     return out;
00358   }
00361   template void YamlFileWriter::messageToFile
00362     (stdr_msgs::SoundSensorMsg msg,std::string file_name);
00363   
00365   template <>
00366   YAML::Emitter& operator << <stdr_msgs::SoundSensorMsg>
00367     (YAML::Emitter& out, const stdr_msgs::SoundSensorMsg& msg)
00368   {
00369     out << YAML::BeginMap;
00370       out << YAML::Key << "sound_sensor";
00371       out << YAML::Value;
00372       out << YAML::BeginMap;
00373         out << YAML::Key << "sound_sensor_specifications";
00374         out << YAML::Value;
00375         out << YAML::BeginMap;
00376           out << YAML::Key << "angle_span" << YAML::Value << msg.angleSpan;
00377           out << YAML::Key << "max_range" << YAML::Value << msg.maxRange;
00378           out << YAML::Key << "frequency" << YAML::Value << msg.frequency;
00379           out << YAML::Key << "frame_id" << YAML::Value << msg.frame_id;
00380           out << YAML::Key << "pose";
00381           out << YAML::Value;
00382           out << YAML::BeginMap;
00383             out << YAML::Key << "x" << YAML::Value << msg.pose.x;
00384             out << YAML::Key << "y" << YAML::Value << msg.pose.y;
00385             out << YAML::Key << "theta" << YAML::Value << msg.pose.theta;
00386           out << YAML::EndMap;
00387         out << YAML::EndMap;
00388       out << YAML::EndMap;
00389     out << YAML::EndMap;
00390     return out;
00391   }
00392   
00395   template void YamlFileWriter::messageToFile
00396     (stdr_msgs::RobotMsg msg,std::string file_name);
00397   
00399   template <>
00400   YAML::Emitter& operator << <stdr_msgs::RobotMsg>
00401     (YAML::Emitter& out, const stdr_msgs::RobotMsg& msg)
00402   {
00403     out << YAML::BeginMap;
00404       out << YAML::Key << "robot";
00405       out << YAML::Value;
00406       out << YAML::BeginMap;
00407         out << YAML::Key << "robot_specifications";
00408         out << YAML::Value;
00409         out << YAML::BeginSeq;
00410           out << msg.footprint;
00411           out << YAML::BeginMap;
00412             out << YAML::Key << "initial_pose";
00413             out << YAML::Value;
00414             out << YAML::BeginMap;
00415               out << YAML::Key << "x" << YAML::Value << msg.initialPose.x;
00416               out << YAML::Key << "y" << YAML::Value << msg.initialPose.y;
00417               out << YAML::Key << "theta" << YAML::Value << msg.initialPose.theta;
00418             out << YAML::EndMap;
00419           out << YAML::EndMap;
00420           for(unsigned int i = 0 ; i < msg.laserSensors.size() ; i++)
00421           {
00422             out << msg.laserSensors[i];
00423           }
00424           for(unsigned int i = 0 ; i < msg.sonarSensors.size() ; i++)
00425           {
00426             out << msg.sonarSensors[i];
00427           }
00428           for(unsigned int i = 0 ; i < msg.rfidSensors.size() ; i++)
00429           {
00430             out << msg.rfidSensors[i];
00431           }
00432           for(unsigned int i = 0 ; i < msg.co2Sensors.size() ; i++)
00433           {
00434             out << msg.co2Sensors[i];
00435           }
00436           for(unsigned int i = 0 ; i < msg.thermalSensors.size() ; i++)
00437           {
00438             out << msg.thermalSensors[i];
00439           }
00440           for(unsigned int i = 0 ; i < msg.soundSensors.size() ; i++)
00441           {
00442             out << msg.soundSensors[i];
00443           }
00444 
00445           
00446           out << msg.kinematicModel;
00447 
00448         out << YAML::EndSeq;
00449       out << YAML::EndMap;
00450     out << YAML::EndMap;
00451     return out;
00452   }
00454   
00461   template <class T>
00462   void YamlFileWriter::messageToFile(T msg,std::string file_name)
00463   {
00464     YAML::Emitter out;
00465     out << msg;
00466     
00467     std::ofstream sensorYamlFile;    
00468     sensorYamlFile.open(file_name.c_str());
00469     sensorYamlFile << out.c_str();
00470     sensorYamlFile.close();
00471   }
00472 
00473 }
00474