Go to the documentation of this file.00001 #ifndef __C_KEY_VALUE_PAIR_H__
00002 #define __C_KEY_VALUE_PAIR_H__
00003
00004
00005 #include <list>
00006 #include <string>
00007
00008 #include <designator_integration_msgs/KeyValuePair.h>
00009 #include <ros/ros.h>
00010 #include <algorithm>
00011 #include <geometry_msgs/PoseStamped.h>
00012
00013 using namespace std;
00014
00015
00016 enum ValueType {
00017 STRING = designator_integration_msgs::KeyValuePair::TYPE_STRING,
00018 FLOAT = designator_integration_msgs::KeyValuePair::TYPE_FLOAT,
00019 DATA = designator_integration_msgs::KeyValuePair::TYPE_DATA,
00020 LIST = designator_integration_msgs::KeyValuePair::TYPE_LIST,
00021 POSESTAMPED = designator_integration_msgs::KeyValuePair::TYPE_POSESTAMPED,
00022 POSE = designator_integration_msgs::KeyValuePair::TYPE_POSE,
00023 DESIGNATOR_ACTION = designator_integration_msgs::KeyValuePair::TYPE_DESIGNATOR_ACTION,
00024 DESIGNATOR_OBJECT = designator_integration_msgs::KeyValuePair::TYPE_DESIGNATOR_OBJECT,
00025 DESIGNATOR_LOCATION = designator_integration_msgs::KeyValuePair::TYPE_DESIGNATOR_LOCATION
00026 };
00027
00028
00029 class CKeyValuePair {
00030 private:
00031 int m_nID;
00032 int m_nParent;
00033 string m_strKey;
00034 string m_strValue;
00035 double m_fValue;
00036 char *m_acValue;
00037 unsigned int m_unValueLength;
00038 geometry_msgs::Pose m_posPoseValue;
00039 geometry_msgs::PoseStamped m_psPoseStampedValue;
00040
00041 protected:
00042 enum ValueType m_evtType;
00043 list<CKeyValuePair*> m_lstChildren;
00044
00045 public:
00046 CKeyValuePair();
00047 CKeyValuePair(string strKey);
00048 CKeyValuePair(string strKey, string strValue);
00049 CKeyValuePair(string strKey, float fValue);
00050 CKeyValuePair(string strKey, char *acValue, unsigned int unLength);
00051 CKeyValuePair(string strKey, geometry_msgs::Pose posPoseValue);
00052 CKeyValuePair(string strKey, geometry_msgs::PoseStamped psPoseStampedValue);
00053 CKeyValuePair(designator_integration_msgs::KeyValuePair kvpContent);
00054 CKeyValuePair(list<CKeyValuePair*> lstChildren);
00055 ~CKeyValuePair();
00056
00057 void init();
00058 void fillWithKeyValueContent(designator_integration_msgs::KeyValuePair kvpContent);
00059 enum ValueType type();
00060
00061 string stringValue();
00062 string stringValue(string strChildKey);
00063 float floatValue();
00064 float floatValue(string strChildKey);
00065 geometry_msgs::PoseStamped poseStampedValue();
00066 geometry_msgs::PoseStamped poseStampedValue(string strChildKey);
00067 geometry_msgs::Pose poseValue();
00068 geometry_msgs::Pose poseValue(string strChildKey);
00069 char* dataValue();
00070 unsigned int dataValueLength();
00071 char* dataValue(unsigned int &unLength);
00072
00073 int id();
00074 int parent();
00075 string key();
00076
00077 void setID(int nID);
00078 void setParent(int nParent);
00079
00080 void setValue(string strValue);
00081 void setValue(float fValue);
00082 void setValue(geometry_msgs::PoseStamped psPoseStampedValue);
00083 void setValue(geometry_msgs::Pose psPoseValue);
00084 void setValue(void* vdValue, unsigned int unLength);
00085 void setValue(enum ValueType evtType, list<CKeyValuePair*> lstDescription);
00086 void clearDataValue();
00087
00088 void setValue(string strKey, string strValue);
00089 void setValue(string strKey, float fValue);
00090 void setValue(string strKey, geometry_msgs::PoseStamped psPoseStampedValue);
00091 void setValue(string strKey, geometry_msgs::Pose psPoseValue);
00092 void setValue(string strKey, char *acValue, int nLength);
00093
00094
00095 void setValue(string strKey, enum ValueType evtType, list<CKeyValuePair*> lstDescription);
00096 void setLocationDesignatorDescription(string strKey, enum ValueType evtType, list<CKeyValuePair*> lstDescription);
00097 void setActionDesignatorDescription(string strKey, list<CKeyValuePair*> lstDescription);
00098 void setObjectDesignatorDescription(string strKey, list<CKeyValuePair*> lstDescription);
00099
00100 void setKey(string strKey);
00101 void setType(enum ValueType evtType);
00102
00103 CKeyValuePair *addChild(string strKey, bool bAppendNew = false);
00104 list<CKeyValuePair*> children();
00105 void setChildren(list<CKeyValuePair*> lstChildren);
00106
00107 void printPair(int nSpaceOffset, bool bOffsetRegular = true, bool bNewline = true);
00108 void printSpaces(int nSpaces);
00109
00110 void addChild(CKeyValuePair *ckvpChildAdd);
00111 CKeyValuePair *addChild(string strKey, string strValue);
00112 CKeyValuePair *addChild(string strKey, float fValue);
00113 CKeyValuePair *addChild(string strKey, geometry_msgs::PoseStamped psPoseStampedValue);
00114 CKeyValuePair *addChild(string strKey, geometry_msgs::Pose psPoseValue);
00115 CKeyValuePair *addChild(string strKey, char *acValue, unsigned int unLength);
00116 CKeyValuePair *addChild(string strKey, enum ValueType evtType, list<CKeyValuePair*> lstDescription);
00117
00118 vector<designator_integration_msgs::KeyValuePair> serializeToMessage(int nParent, int nID);
00119 CKeyValuePair *childForKey(string strKey);
00120 bool removeChildForKey(string strKey);
00121
00122 void clear();
00123
00124 CKeyValuePair* copy();
00125
00126 list<string> keys();
00127 };
00128
00129
00130 #endif