stdr_parser_yaml_file_writer.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002    STDR Simulator - Simple Two DImensional Robot Simulator
00003    Copyright (C) 2013 STDR Simulator
00004    This program is free software; you can redistribute it and/or modify
00005    it under the terms of the GNU General Public License as published by
00006    the Free Software Foundation; either version 3 of the License, or
00007    (at your option) any later version.
00008    This program is distributed in the hope that it will be useful,
00009    but WITHOUT ANY WARRANTY; without even the implied warranty of
00010    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00011    GNU General Public License for more details.
00012    You should have received a copy of the GNU General Public License
00013    along with this program; if not, write to the Free Software Foundation,
00014    Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301  USA
00015    
00016    Authors : 
00017    * Manos Tsardoulias, etsardou@gmail.com
00018    * Aris Thallas, aris.thallas@gmail.com
00019    * Chris Zalidis, zalidis@gmail.com 
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::LaserSensorMsg msg,std::string file_name);
00126   
00128   template <>
00129   YAML::Emitter& operator << <stdr_msgs::LaserSensorMsg>
00130     (YAML::Emitter& out, const stdr_msgs::LaserSensorMsg& msg)
00131   {
00132     out << YAML::BeginMap;
00133       out << YAML::Key << "laser";
00134       out << YAML::Value;
00135       out << YAML::BeginMap;
00136         out << YAML::Key << "laser_specifications";
00137         out << YAML::Value;
00138         out << YAML::BeginMap;
00139           out << YAML::Key << "max_angle" << YAML::Value << msg.maxAngle;
00140           out << YAML::Key << "min_angle" << YAML::Value << msg.minAngle;
00141           out << YAML::Key << "max_range" << YAML::Value << msg.maxRange;
00142           out << YAML::Key << "min_range" << YAML::Value << msg.minRange;
00143           out << YAML::Key << "num_rays" << YAML::Value << msg.numRays;
00144           out << YAML::Key << "frequency" << YAML::Value << msg.frequency;
00145           out << YAML::Key << "frame_id" << YAML::Value << msg.frame_id;
00146           out << YAML::Key << "pose";
00147           out << YAML::Value;
00148           out << YAML::BeginMap;
00149             out << YAML::Key << "x" << YAML::Value << msg.pose.x;
00150             out << YAML::Key << "y" << YAML::Value << msg.pose.y;
00151             out << YAML::Key << "theta" << YAML::Value << msg.pose.theta;
00152           out << YAML::EndMap;
00153           out << YAML::Key << "noise";
00154           out << YAML::Value;
00155           out << YAML::BeginMap;
00156             out << YAML::Key << "noise_specifications";
00157             out << YAML::Value;
00158             out << YAML::BeginMap;
00159               out << YAML::Key << "noise_mean";
00160               out << YAML::Value << msg.noise.noiseMean;
00161               out << YAML::Key << "noise_std";
00162               out << YAML::Value << msg.noise.noiseStd;
00163             out << YAML::EndMap;
00164           out << YAML::EndMap;
00165         out << YAML::EndMap;
00166       out << YAML::EndMap;
00167     out << YAML::EndMap;
00168     return out;
00169   }
00170   
00173   template void YamlFileWriter::messageToFile
00174     (stdr_msgs::SonarSensorMsg msg,std::string file_name);
00175   
00177   template <>
00178   YAML::Emitter& operator << <stdr_msgs::SonarSensorMsg>
00179     (YAML::Emitter& out, const stdr_msgs::SonarSensorMsg& msg)
00180   {
00181     out << YAML::BeginMap;
00182       out << YAML::Key << "sonar";
00183       out << YAML::Value;
00184       out << YAML::BeginMap;
00185         out << YAML::Key << "sonar_specifications";
00186         out << YAML::Value;
00187         out << YAML::BeginMap;
00188           out << YAML::Key << "cone_angle" << YAML::Value << msg.coneAngle;
00189           out << YAML::Key << "max_range" << YAML::Value << msg.maxRange;
00190           out << YAML::Key << "min_range" << YAML::Value << msg.minRange;
00191           out << YAML::Key << "frequency" << YAML::Value << msg.frequency;
00192           out << YAML::Key << "frame_id" << YAML::Value << msg.frame_id;
00193           out << YAML::Key << "pose";
00194           out << YAML::Value;
00195           out << YAML::BeginMap;
00196             out << YAML::Key << "x" << YAML::Value << msg.pose.x;
00197             out << YAML::Key << "y" << YAML::Value << msg.pose.y;
00198             out << YAML::Key << "theta" << YAML::Value << msg.pose.theta;
00199           out << YAML::EndMap;
00200           out << YAML::Key << "noise";
00201           out << YAML::Value;
00202           out << YAML::BeginMap;
00203             out << YAML::Key << "noise_specifications";
00204             out << YAML::Value;
00205             out << YAML::BeginMap;
00206               out << YAML::Key << "noise_mean";
00207               out << YAML::Value << msg.noise.noiseMean;
00208               out << YAML::Key << "noise_std";
00209               out << YAML::Value << msg.noise.noiseStd;
00210             out << YAML::EndMap;
00211           out << YAML::EndMap;
00212         out << YAML::EndMap;
00213       out << YAML::EndMap;
00214     out << YAML::EndMap;
00215     return out;
00216   }
00219   template void YamlFileWriter::messageToFile
00220     (stdr_msgs::RfidSensorMsg msg,std::string file_name);
00221   
00223   template <>
00224   YAML::Emitter& operator << <stdr_msgs::RfidSensorMsg>
00225     (YAML::Emitter& out, const stdr_msgs::RfidSensorMsg& msg)
00226   {
00227     out << YAML::BeginMap;
00228       out << YAML::Key << "rfid_reader";
00229       out << YAML::Value;
00230       out << YAML::BeginMap;
00231         out << YAML::Key << "rfid_reader_specifications";
00232         out << YAML::Value;
00233         out << YAML::BeginMap;
00234           out << YAML::Key << "angle_span" << YAML::Value << msg.angleSpan;
00235           out << YAML::Key << "max_range" << YAML::Value << msg.maxRange;
00236           out << YAML::Key << "signal_cutoff" << YAML::Value << msg.signalCutoff;
00237           out << YAML::Key << "frequency" << YAML::Value << msg.frequency;
00238           out << YAML::Key << "frame_id" << YAML::Value << msg.frame_id;
00239           out << YAML::Key << "pose";
00240           out << YAML::Value;
00241           out << YAML::BeginMap;
00242             out << YAML::Key << "x" << YAML::Value << msg.pose.x;
00243             out << YAML::Key << "y" << YAML::Value << msg.pose.y;
00244             out << YAML::Key << "theta" << YAML::Value << msg.pose.theta;
00245           out << YAML::EndMap;
00246         out << YAML::EndMap;
00247       out << YAML::EndMap;
00248     out << YAML::EndMap;
00249     return out;
00250   }
00253   template void YamlFileWriter::messageToFile
00254     (stdr_msgs::CO2SensorMsg msg,std::string file_name);
00255   
00257   template <>
00258   YAML::Emitter& operator << <stdr_msgs::CO2SensorMsg>
00259     (YAML::Emitter& out, const stdr_msgs::CO2SensorMsg& msg)
00260   {
00261     out << YAML::BeginMap;
00262       out << YAML::Key << "co2_sensor";
00263       out << YAML::Value;
00264       out << YAML::BeginMap;
00265         out << YAML::Key << "co2_sensor_specifications";
00266         out << YAML::Value;
00267         out << YAML::BeginMap;
00268           //~ out << YAML::Key << "angle_span" << YAML::Value << msg.angleSpan;
00269           out << YAML::Key << "max_range" << YAML::Value << msg.maxRange;
00270           //~ out << YAML::Key << "signal_cutoff" << YAML::Value << msg.signalCutoff;
00271           out << YAML::Key << "frequency" << YAML::Value << msg.frequency;
00272           out << YAML::Key << "frame_id" << YAML::Value << msg.frame_id;
00273           out << YAML::Key << "pose";
00274           out << YAML::Value;
00275           out << YAML::BeginMap;
00276             out << YAML::Key << "x" << YAML::Value << msg.pose.x;
00277             out << YAML::Key << "y" << YAML::Value << msg.pose.y;
00278             out << YAML::Key << "theta" << YAML::Value << msg.pose.theta;
00279           out << YAML::EndMap;
00280         out << YAML::EndMap;
00281       out << YAML::EndMap;
00282     out << YAML::EndMap;
00283     return out;
00284   }
00287   template void YamlFileWriter::messageToFile
00288     (stdr_msgs::ThermalSensorMsg msg,std::string file_name);
00289   
00291   template <>
00292   YAML::Emitter& operator << <stdr_msgs::ThermalSensorMsg>
00293     (YAML::Emitter& out, const stdr_msgs::ThermalSensorMsg& msg)
00294   {
00295     out << YAML::BeginMap;
00296       out << YAML::Key << "thermal_sensor";
00297       out << YAML::Value;
00298       out << YAML::BeginMap;
00299         out << YAML::Key << "thermal_sensor_specifications";
00300         out << YAML::Value;
00301         out << YAML::BeginMap;
00302           out << YAML::Key << "angle_span" << YAML::Value << msg.angleSpan;
00303           out << YAML::Key << "max_range" << YAML::Value << msg.maxRange;
00304           out << YAML::Key << "frequency" << YAML::Value << msg.frequency;
00305           out << YAML::Key << "frame_id" << YAML::Value << msg.frame_id;
00306           out << YAML::Key << "pose";
00307           out << YAML::Value;
00308           out << YAML::BeginMap;
00309             out << YAML::Key << "x" << YAML::Value << msg.pose.x;
00310             out << YAML::Key << "y" << YAML::Value << msg.pose.y;
00311             out << YAML::Key << "theta" << YAML::Value << msg.pose.theta;
00312           out << YAML::EndMap;
00313         out << YAML::EndMap;
00314       out << YAML::EndMap;
00315     out << YAML::EndMap;
00316     return out;
00317   }
00320   template void YamlFileWriter::messageToFile
00321     (stdr_msgs::SoundSensorMsg msg,std::string file_name);
00322   
00324   template <>
00325   YAML::Emitter& operator << <stdr_msgs::SoundSensorMsg>
00326     (YAML::Emitter& out, const stdr_msgs::SoundSensorMsg& msg)
00327   {
00328     out << YAML::BeginMap;
00329       out << YAML::Key << "sound_sensor";
00330       out << YAML::Value;
00331       out << YAML::BeginMap;
00332         out << YAML::Key << "sound_sensor_specifications";
00333         out << YAML::Value;
00334         out << YAML::BeginMap;
00335           out << YAML::Key << "angle_span" << YAML::Value << msg.angleSpan;
00336           out << YAML::Key << "max_range" << YAML::Value << msg.maxRange;
00337           out << YAML::Key << "frequency" << YAML::Value << msg.frequency;
00338           out << YAML::Key << "frame_id" << YAML::Value << msg.frame_id;
00339           out << YAML::Key << "pose";
00340           out << YAML::Value;
00341           out << YAML::BeginMap;
00342             out << YAML::Key << "x" << YAML::Value << msg.pose.x;
00343             out << YAML::Key << "y" << YAML::Value << msg.pose.y;
00344             out << YAML::Key << "theta" << YAML::Value << msg.pose.theta;
00345           out << YAML::EndMap;
00346         out << YAML::EndMap;
00347       out << YAML::EndMap;
00348     out << YAML::EndMap;
00349     return out;
00350   }
00351   
00354   template void YamlFileWriter::messageToFile
00355     (stdr_msgs::RobotMsg msg,std::string file_name);
00356   
00358   template <>
00359   YAML::Emitter& operator << <stdr_msgs::RobotMsg>
00360     (YAML::Emitter& out, const stdr_msgs::RobotMsg& msg)
00361   {
00362     out << YAML::BeginMap;
00363       out << YAML::Key << "robot";
00364       out << YAML::Value;
00365       out << YAML::BeginMap;
00366         out << YAML::Key << "robot_specifications";
00367         out << YAML::Value;
00368         out << YAML::BeginSeq;
00369           out << msg.footprint;
00370           out << YAML::BeginMap;
00371             out << YAML::Key << "initial_pose";
00372             out << YAML::Value;
00373             out << YAML::BeginMap;
00374               out << YAML::Key << "x" << YAML::Value << msg.initialPose.x;
00375               out << YAML::Key << "y" << YAML::Value << msg.initialPose.y;
00376               out << YAML::Key << "theta" << YAML::Value << msg.initialPose.theta;
00377             out << YAML::EndMap;
00378           out << YAML::EndMap;
00379           for(unsigned int i = 0 ; i < msg.laserSensors.size() ; i++)
00380           {
00381             out << msg.laserSensors[i];
00382           }
00383           for(unsigned int i = 0 ; i < msg.sonarSensors.size() ; i++)
00384           {
00385             out << msg.sonarSensors[i];
00386           }
00387           for(unsigned int i = 0 ; i < msg.rfidSensors.size() ; i++)
00388           {
00389             out << msg.rfidSensors[i];
00390           }
00391           for(unsigned int i = 0 ; i < msg.co2Sensors.size() ; i++)
00392           {
00393             out << msg.co2Sensors[i];
00394           }
00395           for(unsigned int i = 0 ; i < msg.thermalSensors.size() ; i++)
00396           {
00397             out << msg.thermalSensors[i];
00398           }
00399           for(unsigned int i = 0 ; i < msg.soundSensors.size() ; i++)
00400           {
00401             out << msg.soundSensors[i];
00402           }
00403         out << YAML::EndSeq;
00404       out << YAML::EndMap;
00405     out << YAML::EndMap;
00406     return out;
00407   }
00409   
00416   template <class T>
00417   void YamlFileWriter::messageToFile(T msg,std::string file_name)
00418   {
00419     YAML::Emitter out;
00420     out << msg;
00421     
00422     std::ofstream sensorYamlFile;    
00423     sensorYamlFile.open(file_name.c_str());
00424     sensorYamlFile << out.c_str();
00425     sensorYamlFile.close();
00426   }
00427 
00428 }
00429 


stdr_parser
Author(s): Manos Tsardoulias, Chris Zalidis, Aris Thallas
autogenerated on Wed Sep 2 2015 03:36:18