00001 #include <designators/CDesignator.h> 00002 00003 00004 CDesignator::CDesignator() : CKeyValuePair() { 00005 this->m_edtType = OBJECT; 00006 } 00007 00008 CDesignator::CDesignator(CDesignator* cdTemplate) { 00009 this->setType(cdTemplate->type()); 00010 this->setDescription(cdTemplate->description()); 00011 } 00012 00013 CDesignator::CDesignator(designator_integration_msgs::Designator desigContent) { 00014 this->fillFromDesignatorMsg(desigContent); 00015 } 00016 00017 CDesignator::CDesignator(enum DesignatorType edtType, CKeyValuePair* ckvpDescription) { 00018 if(ckvpDescription) { 00019 this->fillFromDescription(edtType, ckvpDescription->children()); 00020 } else { 00021 this->setType(edtType); 00022 } 00023 } 00024 00025 CDesignator::CDesignator(enum DesignatorType edtType, list<CKeyValuePair*> lstDescription) { 00026 this->fillFromDescription(edtType, lstDescription); 00027 } 00028 00029 void CDesignator::fillFromDescription(enum DesignatorType edtType, list<CKeyValuePair*> lstDescription) { 00030 list<CKeyValuePair*> lstDescriptionNew; 00031 00032 for(list<CKeyValuePair*>::iterator itKVP = lstDescription.begin(); 00033 itKVP != lstDescription.end(); 00034 itKVP++) { 00035 lstDescriptionNew.push_back((*itKVP)->copy()); 00036 } 00037 00038 this->setDescription(lstDescriptionNew); 00039 this->setType(edtType); 00040 } 00041 00042 void CDesignator::setDescription(list<CKeyValuePair*> lstDescription) { 00043 m_lstChildren = lstDescription; 00044 } 00045 00046 list<CKeyValuePair*> CDesignator::description() { 00047 return m_lstChildren; 00048 } 00049 00050 void CDesignator::setType(enum DesignatorType edtType) { 00051 m_edtType = edtType; 00052 00053 enum ValueType evtType = DESIGNATOR_OBJECT; 00054 switch(edtType) { 00055 case ACTION: 00056 evtType = DESIGNATOR_ACTION; 00057 break; 00058 00059 case OBJECT: 00060 evtType = DESIGNATOR_OBJECT; 00061 break; 00062 00063 case LOCATION: 00064 evtType = DESIGNATOR_LOCATION; 00065 break; 00066 00067 default: 00068 break; 00069 } 00070 00071 m_evtType = evtType; 00072 } 00073 00074 void CDesignator::fillFromDesignatorMsg(designator_integration_msgs::Designator desigContent) { 00075 m_edtType = (enum DesignatorType)desigContent.type; 00076 00077 list<CKeyValuePair*> lstKVPs; 00078 for(vector<designator_integration_msgs::KeyValuePair>::iterator itKVP = desigContent.description.begin(); 00079 itKVP != desigContent.description.end(); 00080 itKVP++) { 00081 designator_integration_msgs::KeyValuePair kvpCurrent = *itKVP; 00082 00083 CKeyValuePair *ckvpCurrent = new CKeyValuePair(kvpCurrent); 00084 lstKVPs.push_back(ckvpCurrent); 00085 } 00086 00087 while(lstKVPs.size() > 0) { 00088 for(list<CKeyValuePair*>::iterator itKVP = lstKVPs.begin(); 00089 itKVP != lstKVPs.end(); 00090 itKVP++) { 00091 CKeyValuePair *kvpCurrent = *itKVP; 00092 bool bFoundChild = false; 00093 00094 for(list<CKeyValuePair*>::iterator itKVPInspect = lstKVPs.begin(); 00095 itKVPInspect != lstKVPs.end(); 00096 itKVPInspect++) { 00097 CKeyValuePair *kvpInspect = *itKVPInspect; 00098 00099 if(kvpInspect != kvpCurrent && kvpInspect->parent() == kvpCurrent->id()) { 00100 bFoundChild = true; 00101 break; 00102 } 00103 } 00104 00105 if(!bFoundChild) { 00106 bool bFoundParent = false; 00107 00108 for(list<CKeyValuePair*>::iterator itKVPInspect = lstKVPs.begin(); 00109 itKVPInspect != lstKVPs.end(); 00110 itKVPInspect++) { 00111 CKeyValuePair *kvpInspect = *itKVPInspect; 00112 00113 if(kvpInspect != kvpCurrent && kvpInspect->id() == kvpCurrent->parent()) { 00114 kvpInspect->addChild(kvpCurrent); 00115 lstKVPs.remove(kvpCurrent); 00116 bFoundParent = true; 00117 break; 00118 } 00119 } 00120 00121 if(bFoundParent) { 00122 break; 00123 } else { 00124 m_lstChildren.push_back(kvpCurrent); 00125 lstKVPs.remove(kvpCurrent); 00126 break; 00127 } 00128 } 00129 } 00130 } 00131 } 00132 00133 enum DesignatorType CDesignator::type() { 00134 return m_edtType; 00135 } 00136 00137 void CDesignator::printDesignator() { 00138 for(list<CKeyValuePair*>::iterator itKVP = m_lstChildren.begin(); 00139 itKVP != m_lstChildren.end(); 00140 itKVP++) { 00141 CKeyValuePair *kvpCurrent = *itKVP; 00142 00143 kvpCurrent->printPair(0); 00144 cout << endl; 00145 } 00146 } 00147 00148 designator_integration_msgs::Designator CDesignator::serializeToMessage() { 00149 designator_integration_msgs::Designator msgDesig; 00150 msgDesig.type = (int)m_edtType; 00151 00152 int nHighestID = 0; 00153 vector<designator_integration_msgs::KeyValuePair> vecKVPs; 00154 for(list<CKeyValuePair*>::iterator itKVP = m_lstChildren.begin(); 00155 itKVP != m_lstChildren.end(); 00156 itKVP++) { 00157 CKeyValuePair *ckvpCurrent = *itKVP; 00158 00159 vector<designator_integration_msgs::KeyValuePair> vecKVPMsgs = ckvpCurrent->serializeToMessage(0, nHighestID + 1); 00160 for(vector<designator_integration_msgs::KeyValuePair>::iterator itKVPMsg = vecKVPMsgs.begin(); 00161 itKVPMsg != vecKVPMsgs.end(); 00162 itKVPMsg++) { 00163 designator_integration_msgs::KeyValuePair kvpCurrent = *itKVPMsg; 00164 00165 if(kvpCurrent.id > nHighestID) { 00166 nHighestID = kvpCurrent.id; 00167 } 00168 00169 vecKVPs.push_back(kvpCurrent); 00170 } 00171 } 00172 00173 msgDesig.description = vecKVPs; 00174 00175 return msgDesig; 00176 }