xmlPrinter.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * xmlPrinter.hpp
00003  *
00004  *  Created on: Apr 3, 2014
00005  *      Author: Filip Mandic
00006  *
00007  ********************************************************************/
00008 
00009 /*********************************************************************
00010 * Software License Agreement (BSD License)
00011 *
00012 *  Copyright (c) 2014, LABUST, UNIZG-FER
00013 *  All rights reserved.
00014 *
00015 *  Redistribution and use in source and binary forms, with or without
00016 *  modification, are permitted provided that the following conditions
00017 *  are met:
00018 *
00019 *   * Redistributions of source code must retain the above copyright
00020 *     notice, this list of conditions and the following disclaimer.
00021 *   * Redistributions in binary form must reproduce the above
00022 *     copyright notice, this list of conditions and the following
00023 *     disclaimer in the documentation and/or other materials provided
00024 *     with the distribution.
00025 *   * Neither the name of the LABUST nor the names of its
00026 *     contributors may be used to endorse or promote products derived
00027 *     from this software without specific prior written permission.
00028 *
00029 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00030 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00031 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00032 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00033 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00034 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00035 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00036 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00037 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00038 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00039 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00040 *  POSSIBILITY OF SUCH DAMAGE.
00041 *********************************************************************/
00042 
00043 #ifndef XMLPRINTER_HPP_
00044 #define XMLPRINTER_HPP_
00045 
00046 #include <labust_mission/labustMission.hpp>
00047 #include <tinyxml2.h>
00048 
00049 using namespace tinyxml2;
00050 using namespace std;
00051 
00052 namespace labust{
00053         namespace utils {
00054 
00055                 /*****************************************************************
00056                  *** WriteXML Class definition
00057                  ****************************************************************/
00058 
00059                 class WriteXML{
00060 
00061                 public:
00062 
00063                         /************************************************************
00064                          *** Class functions
00065                          ************************************************************/
00066 
00067                         WriteXML();
00068 
00069                         void addMission();
00070 
00071                         void addEvent();
00072 
00073                         void saveXML(string fileName);
00074 
00075                         void addXMLNode(XMLNode* parentNode, string nodeName, string attrName, string attrValue, double value);
00076 
00077                         void addGo2point_FA(double north, double east, double speed, double victoryRadius);
00078 
00079                         void addGo2point_UA(double north, double east, double speed, double victoryRadius);
00080 
00081                         void addDynamic_positioning(double north, double east, double heading);
00082 
00083                         void addCourse_keeping_FA(double course, double speed, double heading);
00084 
00085                         void addCourse_keeping_UA(double course, double speed);
00086 
00087 
00088                         /************************************************************
00089                          *** Class variables
00090                          ************************************************************/
00091 
00092                         XMLDocument doc;
00093 
00094                         XMLNode *mission;
00095                         XMLNode *main;
00096                         XMLNode *primitive;
00097                         XMLNode *param;
00098                         XMLNode *idNode;
00099                         XMLNode *events;
00100 
00101                         int id;
00102 
00103                 };
00104 
00105                 WriteXML::WriteXML():id(0){
00106 
00107                 }
00108 
00109                 void WriteXML::addMission(){
00110                         main = doc.NewElement("main");
00111                         mission = doc.NewElement("mission");
00112                         doc.InsertEndChild(main);
00113                         main->InsertEndChild(mission);
00114                         id = 0;
00115                 }
00116 
00117                 void WriteXML::addEvent(){
00118 
00119                         events = doc.NewElement("events");
00120                         doc.InsertEndChild(events); // Provjeri ubacuje li u pravi parent
00121                 }
00122 
00123                 void WriteXML::saveXML(string fileName){
00124 
00125                         doc.SaveFile( fileName.c_str() );
00126                         doc.Clear();
00127                         ROS_ERROR("Mission generated.");
00128                 }
00129 
00130 
00131                 void WriteXML::addXMLNode(XMLNode* parentNode, string nodeName, string attrName, string attrValue, double value){
00132 
00133                         XMLNode *node;
00134                         string text;
00135                         node = doc.NewElement(nodeName.c_str());
00136                         if(attrName.empty() == 0)
00137                                 node->ToElement()->SetAttribute(attrName.c_str(),attrValue.c_str());
00138 
00139                         text.assign(static_cast<ostringstream*>( &(ostringstream() << value) )->str());
00140                         node->InsertEndChild(doc.NewText(text.c_str()));
00141                         parentNode->InsertEndChild(node);
00142                 }
00143 
00144                 void WriteXML::addGo2point_UA(double north, double east, double speed, double victoryRadius){
00145 
00146                         id++;
00147 
00148                         primitive = doc.NewElement("primitive");
00149                         primitive->ToElement()->SetAttribute("name","go2point_UA");
00150 
00151                         addXMLNode(primitive,"id","","",id);
00152 
00153                         addXMLNode(primitive,"param","name","north",north);
00154                         addXMLNode(primitive,"param","name","east",east);
00155                         addXMLNode(primitive,"param","name","speed",speed);
00156                         addXMLNode(primitive,"param","name","victory_radius",victoryRadius);
00157 
00158                         mission->InsertEndChild(primitive);
00159                 }
00160 
00161                 void WriteXML::addGo2point_FA(double north, double east, double speed, double victoryRadius){
00162 
00163                         id++;
00164 
00165                         primitive = doc.NewElement("primitive");
00166                         primitive->ToElement()->SetAttribute("name","go2point_FA");
00167 
00168                         addXMLNode(primitive,"id","","",id);
00169 
00170                         addXMLNode(primitive,"param","name","north",north);
00171                         addXMLNode(primitive,"param","name","east",east);
00172                         //addXMLNode(primitive,"param","name","heading",heading);
00173                         addXMLNode(primitive,"param","name","speed",speed);
00174                         addXMLNode(primitive,"param","name","victory_radius",victoryRadius);
00175 
00176                         mission->InsertEndChild(primitive);
00177                 }
00178 
00179                 void WriteXML::addDynamic_positioning(double north, double east, double heading){
00180 
00181                         id++;
00182 
00183                         primitive = doc.NewElement("primitive");
00184                         primitive->ToElement()->SetAttribute("name","dynamic_positioning");
00185 
00186                         addXMLNode(primitive,"id","","",id);
00187 
00188                         addXMLNode(primitive,"param","name","north",north);
00189                         addXMLNode(primitive,"param","name","east",east);
00190                         addXMLNode(primitive,"param","name","heading",heading);
00191                         addXMLNode(primitive,"param","name","timeout",0);
00192 
00193                         mission->InsertEndChild(primitive);
00194                 }
00195 
00196                 void WriteXML::addCourse_keeping_FA(double course, double speed, double heading){
00197 
00198                         id++;
00199 
00200                         primitive = doc.NewElement("primitive");
00201                         primitive->ToElement()->SetAttribute("name","course_keeping_FA");
00202 
00203                         addXMLNode(primitive,"id","","",id);
00204 
00205                         addXMLNode(primitive,"param","name","course",course);
00206                         addXMLNode(primitive,"param","name","speed",speed);
00207                         addXMLNode(primitive,"param","name","heading",heading);
00208                         addXMLNode(primitive,"param","name","timeout",10);
00209 
00210                         mission->InsertEndChild(primitive);
00211                 }
00212 
00213                 void WriteXML::addCourse_keeping_UA(double course, double speed){
00214 
00215                         id++;
00216 
00217                         primitive = doc.NewElement("primitive");
00218                         primitive->ToElement()->SetAttribute("name","course_keeping_UA");
00219 
00220                         addXMLNode(primitive,"id","","",id);
00221 
00222                         addXMLNode(primitive,"param","name","course",course);
00223                         addXMLNode(primitive,"param","name","speed",speed);
00224                         addXMLNode(primitive,"param","name","timeout",10);
00225 
00226                         mission->InsertEndChild(primitive);
00227                 }
00228         }
00229 }
00230 
00231 #endif /* XMLPRINTER_HPP_ */


labust_mission
Author(s): Filip Mandic
autogenerated on Fri Aug 28 2015 11:23:04