00001 //\todo prouciti mogucnost primjene inline funkcija 00002 00003 /********************************************************************* 00004 * dataManager.hpp 00005 * 00006 * Created on: Jun 20, 2014 00007 * Author: Filip Mandic 00008 * 00009 ********************************************************************/ 00010 00011 /********************************************************************* 00012 * Software License Agreement (BSD License) 00013 * 00014 * Copyright (c) 2014, LABUST, UNIZG-FER 00015 * All rights reserved. 00016 * 00017 * Redistribution and use in source and binary forms, with or without 00018 * modification, are permitted provided that the following conditions 00019 * are met: 00020 * 00021 * * Redistributions of source code must retain the above copyright 00022 * notice, this list of conditions and the following disclaimer. 00023 * * Redistributions in binary form must reproduce the above 00024 * copyright notice, this list of conditions and the following 00025 * disclaimer in the documentation and/or other materials provided 00026 * with the distribution. 00027 * * Neither the name of the LABUST nor the names of its 00028 * contributors may be used to endorse or promote products derived 00029 * from this software without specific prior written permission. 00030 * 00031 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00032 * "AS IS" AND ANExternalEventY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00033 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00034 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00035 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00036 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00037 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00038 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00039 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00040 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00041 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00042 * POSSIBILITY OF SUCH DAMAGE. 00043 *********************************************************************/ 00044 00045 #ifndef DATAMANAGER_HPP_ 00046 #define DATAMANAGER_HPP_ 00047 00048 #include <labust_mission/labustMission.hpp> 00049 00050 /********************************************************************* 00051 *** DataManager class definition 00052 ********************************************************************/ 00053 00054 namespace labust { 00055 namespace data { 00056 00057 class DataManager{ 00058 00059 public: 00060 00061 /***************************************************************** 00062 *** Class functions 00063 ****************************************************************/ 00064 00065 DataManager(); 00066 00067 void updateStateVar(const auv_msgs::NavSts::ConstPtr& data); 00068 00069 void updateMissionVar(int missionVarID, double value); 00070 00071 void setMissionVar(double value); 00072 00073 void setMissionVarNames(string name); 00074 00075 void updateEventsVar(vector<uint8_t> values); 00076 00077 vector<double> getStateVar(); 00078 00079 vector<double> getMissionVar(); 00080 00081 vector<string> getMissionVarNames(); 00082 00083 vector<uint8_t> getEventsVar(); 00084 00085 void reset(); 00086 00087 00088 /********************************************************************* 00089 *** Class variables 00090 ********************************************************************/ 00091 00092 private: 00093 00094 /* State Hat variables */ 00095 vector<double> stateHatVar; 00096 00097 /* Events data variables */ 00098 vector<uint8_t> eventsVar; 00099 00100 /* Mission specific variables */ 00101 vector<double> missionVar; 00102 vector<string> missionVarNames; 00103 }; 00104 00105 DataManager::DataManager(){ 00106 00107 stateHatVar.resize(stateHatNum); 00108 eventsVar.clear(); 00109 missionVar.clear(); 00110 missionVarNames.clear(); 00111 00112 } 00113 00114 void DataManager::updateStateVar(const auv_msgs::NavSts::ConstPtr& data){ 00115 00116 stateHatVar[u] = data->body_velocity.x; 00117 stateHatVar[v] = data->body_velocity.y; 00118 stateHatVar[w] = data->body_velocity.z; 00119 stateHatVar[r] = data->orientation_rate.yaw; 00120 00121 stateHatVar[x] = data->position.north; 00122 stateHatVar[y] = data->position.east; 00123 stateHatVar[z] = data->position.depth; 00124 stateHatVar[psi] = data->orientation.yaw; 00125 00126 stateHatVar[x_var] = data->position_variance.north; 00127 stateHatVar[y_var] = data->position_variance.east; 00128 stateHatVar[z_var] = data->position_variance.depth; 00129 stateHatVar[psi_var] = data->orientation_variance.yaw; 00130 00131 stateHatVar[alt] = data->altitude; 00132 00133 } 00134 00135 void DataManager::updateMissionVar(int missionVarID, double value){ 00136 00137 missionVar.at(missionVarID-1) = value; 00138 /* OVDJE DODAJ KAKO DA HENDLA EXCEPTION */ 00139 } 00140 00141 void DataManager::setMissionVar(double value){ 00142 00143 missionVar.push_back(value); 00144 } 00145 00146 void DataManager::setMissionVarNames(string name){ 00147 00148 missionVarNames.push_back(name.c_str()); 00149 /* OVDJE DODAJ KAKO DA HENDLA EXCEPTION */ 00150 } 00151 00152 void DataManager::updateEventsVar(vector<uint8_t> values){ 00153 00154 eventsVar = values; 00155 /* OVDJE DODAJ KAKO DA HENDLA EXCEPTION */ 00156 } 00157 00158 vector<double> DataManager::getStateVar(){ 00159 return stateHatVar; 00160 } 00161 00162 vector<double> DataManager::getMissionVar(){ 00163 return missionVar; 00164 } 00165 00166 vector<uint8_t> DataManager::getEventsVar(){ 00167 return eventsVar; 00168 } 00169 00170 vector<string> DataManager::getMissionVarNames(){ 00171 return missionVarNames; 00172 } 00173 00174 void DataManager::reset(){ 00175 00176 missionVar.clear(); 00177 missionVarNames.clear(); 00178 eventsVar.clear(); 00179 } 00180 } 00181 } 00182 00183 #endif /* DATAMANAGER_HPP_ */