Go to the documentation of this file.00001
00018 #include "Transformation/transformationfile_manager_XML.h"
00019 #include <iostream>
00020 #include <fstream>
00021 #include <string>
00022 #include <ros/ros.h>
00023 #ifndef Q_MOC_RUN
00024 #include <boost/foreach.hpp>
00025 #include <boost/property_tree/ptree.hpp>
00026 #include <boost/property_tree/xml_parser.hpp>
00027 #endif
00028
00029 using namespace std;
00030
00031 TransformationFile_Manager_XML::TransformationFile_Manager_XML (string filePath) : Abstract_TransformationFile_Manager(filePath) {}
00032
00033 bool TransformationFile_Manager_XML::writeToFile(Transformation_Data data)
00034 {
00035 boost::property_tree::ptree pt;
00036 ifstream infile(this->filePath);
00037 if (infile.good()) boost::property_tree::read_xml(this->filePath, pt);
00038
00039 boost::property_tree::ptree dataNode;
00040 boost::property_tree::ptree transformLaserScan_Node;
00041 boost::property_tree::ptree transformPTU_Node;
00042
00043 dataNode.put<double>("<xmlattr>.Pan", data.pan);
00044 dataNode.put<double>("<xmlattr>.Tilt", data.tilt);
00045
00046 for (unsigned int i = 0; i < 4; i++)
00047 {
00048 for (unsigned int j = 0; j < 4; j++)
00049 {
00050 std::string name = "<xmlattr>.x_" + std::to_string(i) + std::to_string(j);
00051 transformLaserScan_Node.put<double>(name, data.LaserScan_Frame(i,j));
00052 transformPTU_Node.put<double>(name, data.PTU_Frame(i,j));
00053 }
00054 }
00055 dataNode.add_child("FrameLaserscan", transformLaserScan_Node);
00056 dataNode.add_child("FramePTU", transformPTU_Node);
00057 pt.add_child("TransformationData.DataSet", dataNode);
00058
00059 boost::property_tree::write_xml(this->filePath, pt,std::locale());
00060 return true;
00061 }
00062
00063 std::vector<Transformation_Data> TransformationFile_Manager_XML::readFromFile(string filePath)
00064 {
00065 std::vector<Transformation_Data> output;
00066 boost::property_tree::ptree pt;
00067
00068 read_xml(filePath, pt);
00069
00070 BOOST_FOREACH(boost::property_tree::ptree::value_type &node, pt.get_child("TransformationData"))
00071 {
00072 if (node.first == "DataSet")
00073 {
00074 Transformation_Data data;
00075 data.pan = node.second.get<double>("<xmlattr>.Pan");
00076 data.tilt = node.second.get<double>("<xmlattr>.Tilt");
00077 boost::property_tree::ptree transformLaserScan_Node = node.second.get_child("FrameLaserscan");
00078 boost::property_tree::ptree transformPTU_Node = node.second.get_child("FramePTU");
00079 for (unsigned int i = 0; i < 4; i++)
00080 {
00081 for (unsigned int j = 0; j < 4; j++)
00082 {
00083 std::string name = "<xmlattr>.x_" + std::to_string(i) + std::to_string(j);
00084 data.LaserScan_Frame(i, j) = transformLaserScan_Node.get<double>(name);
00085 data.PTU_Frame(i, j) = transformPTU_Node.get<double>(name);
00086 }
00087 }
00088 output.push_back(data);
00089 }
00090 }
00091 return output;
00092 }
00093
00094 std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> TransformationFile_Manager_XML::readTransformationFromFile(string filePath)
00095 {
00096 std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> re;
00097 return re;
00098 }
00099
00100 bool TransformationFile_Manager_XML::writeTransformationToFile(const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> transformation)
00101 {
00102 return false;
00103 }
00104
00105 bool TransformationFile_Manager_XML::writeCameraOffsetToFile(const PanTiltOffsetTupleList &offsetData)
00106 {
00107 return true;
00108 }