#include <CKeyValuePair.h>

Public Member Functions | |
| CKeyValuePair * | addChild (string strKey, bool bAppendNew=false) |
| void | addChild (CKeyValuePair *ckvpChildAdd) |
| CKeyValuePair * | addChild (string strKey, string strValue) |
| CKeyValuePair * | addChild (string strKey, float fValue) |
| CKeyValuePair * | addChild (string strKey, geometry_msgs::PoseStamped psPoseStampedValue) |
| CKeyValuePair * | addChild (string strKey, geometry_msgs::Pose psPoseValue) |
| CKeyValuePair * | addChild (string strKey, char *acValue, unsigned int unLength) |
| CKeyValuePair * | addChild (string strKey, enum ValueType evtType, list< CKeyValuePair * > lstDescription) |
| CKeyValuePair * | childForKey (string strKey) |
| list< CKeyValuePair * > | children () |
| CKeyValuePair () | |
| CKeyValuePair (string strKey) | |
| CKeyValuePair (string strKey, string strValue) | |
| CKeyValuePair (string strKey, float fValue) | |
| CKeyValuePair (string strKey, char *acValue, unsigned int unLength) | |
| CKeyValuePair (string strKey, geometry_msgs::Pose posPoseValue) | |
| CKeyValuePair (string strKey, geometry_msgs::PoseStamped psPoseStampedValue) | |
| CKeyValuePair (designator_integration_msgs::KeyValuePair kvpContent) | |
| CKeyValuePair (list< CKeyValuePair * > lstChildren) | |
| void | clear () |
| void | clearDataValue () |
| CKeyValuePair * | copy () |
| char * | dataValue () |
| char * | dataValue (unsigned int &unLength) |
| unsigned int | dataValueLength () |
| void | fillWithKeyValueContent (designator_integration_msgs::KeyValuePair kvpContent) |
| float | floatValue () |
| float | floatValue (string strChildKey) |
| int | id () |
| void | init () |
| string | key () |
| list< string > | keys () |
| int | parent () |
| geometry_msgs::PoseStamped | poseStampedValue () |
| geometry_msgs::PoseStamped | poseStampedValue (string strChildKey) |
| geometry_msgs::Pose | poseValue () |
| geometry_msgs::Pose | poseValue (string strChildKey) |
| void | printPair (int nSpaceOffset, bool bOffsetRegular=true, bool bNewline=true) |
| void | printSpaces (int nSpaces) |
| bool | removeChildForKey (string strKey) |
| vector < designator_integration_msgs::KeyValuePair > | serializeToMessage (int nParent, int nID) |
| void | setActionDesignatorDescription (string strKey, list< CKeyValuePair * > lstDescription) |
| void | setChildren (list< CKeyValuePair * > lstChildren) |
| void | setID (int nID) |
| void | setKey (string strKey) |
| void | setLocationDesignatorDescription (string strKey, enum ValueType evtType, list< CKeyValuePair * > lstDescription) |
| void | setObjectDesignatorDescription (string strKey, list< CKeyValuePair * > lstDescription) |
| void | setParent (int nParent) |
| void | setType (enum ValueType evtType) |
| void | setValue (string strValue) |
| void | setValue (float fValue) |
| void | setValue (geometry_msgs::PoseStamped psPoseStampedValue) |
| void | setValue (geometry_msgs::Pose psPoseValue) |
| void | setValue (void *vdValue, unsigned int unLength) |
| void | setValue (enum ValueType evtType, list< CKeyValuePair * > lstDescription) |
| void | setValue (string strKey, string strValue) |
| void | setValue (string strKey, float fValue) |
| void | setValue (string strKey, geometry_msgs::PoseStamped psPoseStampedValue) |
| void | setValue (string strKey, geometry_msgs::Pose psPoseValue) |
| void | setValue (string strKey, char *acValue, int nLength) |
| void | setValue (string strKey, enum ValueType evtType, list< CKeyValuePair * > lstDescription) |
| string | stringValue () |
| string | stringValue (string strChildKey) |
| enum ValueType | type () |
| ~CKeyValuePair () | |
Protected Attributes | |
| enum ValueType | m_evtType |
| list< CKeyValuePair * > | m_lstChildren |
Private Attributes | |
| char * | m_acValue |
| double | m_fValue |
| int | m_nID |
| int | m_nParent |
| geometry_msgs::Pose | m_posPoseValue |
| geometry_msgs::PoseStamped | m_psPoseStampedValue |
| string | m_strKey |
| string | m_strValue |
| unsigned int | m_unValueLength |
Definition at line 29 of file CKeyValuePair.h.
Definition at line 4 of file CKeyValuePair.cpp.
| CKeyValuePair::CKeyValuePair | ( | string | strKey | ) |
Definition at line 8 of file CKeyValuePair.cpp.
| CKeyValuePair::CKeyValuePair | ( | string | strKey, |
| string | strValue | ||
| ) |
Definition at line 13 of file CKeyValuePair.cpp.
| CKeyValuePair::CKeyValuePair | ( | string | strKey, |
| float | fValue | ||
| ) |
Definition at line 19 of file CKeyValuePair.cpp.
| CKeyValuePair::CKeyValuePair | ( | string | strKey, |
| char * | acValue, | ||
| unsigned int | unLength | ||
| ) |
Definition at line 25 of file CKeyValuePair.cpp.
| CKeyValuePair::CKeyValuePair | ( | string | strKey, |
| geometry_msgs::Pose | posPoseValue | ||
| ) |
Definition at line 42 of file CKeyValuePair.cpp.
| CKeyValuePair::CKeyValuePair | ( | string | strKey, |
| geometry_msgs::PoseStamped | psPoseStampedValue | ||
| ) |
Definition at line 36 of file CKeyValuePair.cpp.
| CKeyValuePair::CKeyValuePair | ( | designator_integration_msgs::KeyValuePair | kvpContent | ) |
Definition at line 31 of file CKeyValuePair.cpp.
| CKeyValuePair::CKeyValuePair | ( | list< CKeyValuePair * > | lstChildren | ) |
Definition at line 48 of file CKeyValuePair.cpp.
Definition at line 53 of file CKeyValuePair.cpp.
| CKeyValuePair * CKeyValuePair::addChild | ( | string | strKey, |
| bool | bAppendNew = false |
||
| ) |
Definition at line 173 of file CKeyValuePair.cpp.
| void CKeyValuePair::addChild | ( | CKeyValuePair * | ckvpChildAdd | ) |
Definition at line 189 of file CKeyValuePair.cpp.
| CKeyValuePair * CKeyValuePair::addChild | ( | string | strKey, |
| string | strValue | ||
| ) |
Definition at line 443 of file CKeyValuePair.cpp.
| CKeyValuePair * CKeyValuePair::addChild | ( | string | strKey, |
| float | fValue | ||
| ) |
Definition at line 450 of file CKeyValuePair.cpp.
| CKeyValuePair * CKeyValuePair::addChild | ( | string | strKey, |
| geometry_msgs::PoseStamped | psPoseStampedValue | ||
| ) |
Definition at line 457 of file CKeyValuePair.cpp.
| CKeyValuePair * CKeyValuePair::addChild | ( | string | strKey, |
| geometry_msgs::Pose | psPoseValue | ||
| ) |
Definition at line 464 of file CKeyValuePair.cpp.
| CKeyValuePair * CKeyValuePair::addChild | ( | string | strKey, |
| char * | acValue, | ||
| unsigned int | unLength | ||
| ) |
Definition at line 471 of file CKeyValuePair.cpp.
| CKeyValuePair * CKeyValuePair::addChild | ( | string | strKey, |
| enum ValueType | evtType, | ||
| list< CKeyValuePair * > | lstDescription | ||
| ) |
Definition at line 416 of file CKeyValuePair.cpp.
| CKeyValuePair * CKeyValuePair::childForKey | ( | string | strKey | ) |
Definition at line 524 of file CKeyValuePair.cpp.
| list< CKeyValuePair * > CKeyValuePair::children | ( | ) |
Definition at line 194 of file CKeyValuePair.cpp.
| void CKeyValuePair::clear | ( | ) |
Definition at line 635 of file CKeyValuePair.cpp.
| void CKeyValuePair::clearDataValue | ( | ) |
Definition at line 384 of file CKeyValuePair.cpp.
Definition at line 639 of file CKeyValuePair.cpp.
| char * CKeyValuePair::dataValue | ( | ) |
Definition at line 139 of file CKeyValuePair.cpp.
| char * CKeyValuePair::dataValue | ( | unsigned int & | unLength | ) |
Definition at line 147 of file CKeyValuePair.cpp.
| unsigned int CKeyValuePair::dataValueLength | ( | ) |
Definition at line 143 of file CKeyValuePair.cpp.
| void CKeyValuePair::fillWithKeyValueContent | ( | designator_integration_msgs::KeyValuePair | kvpContent | ) |
Definition at line 67 of file CKeyValuePair.cpp.
| float CKeyValuePair::floatValue | ( | ) |
Definition at line 111 of file CKeyValuePair.cpp.
| float CKeyValuePair::floatValue | ( | string | strChildKey | ) |
Definition at line 563 of file CKeyValuePair.cpp.
| int CKeyValuePair::id | ( | ) |
Definition at line 161 of file CKeyValuePair.cpp.
| void CKeyValuePair::init | ( | ) |
Definition at line 57 of file CKeyValuePair.cpp.
| string CKeyValuePair::key | ( | ) |
Definition at line 169 of file CKeyValuePair.cpp.
| list< string > CKeyValuePair::keys | ( | ) |
Definition at line 662 of file CKeyValuePair.cpp.
| int CKeyValuePair::parent | ( | ) |
Definition at line 165 of file CKeyValuePair.cpp.
| geometry_msgs::PoseStamped CKeyValuePair::poseStampedValue | ( | ) |
Definition at line 153 of file CKeyValuePair.cpp.
| geometry_msgs::PoseStamped CKeyValuePair::poseStampedValue | ( | string | strChildKey | ) |
Definition at line 573 of file CKeyValuePair.cpp.
| geometry_msgs::Pose CKeyValuePair::poseValue | ( | ) |
Definition at line 157 of file CKeyValuePair.cpp.
| geometry_msgs::Pose CKeyValuePair::poseValue | ( | string | strChildKey | ) |
Definition at line 584 of file CKeyValuePair.cpp.
| void CKeyValuePair::printPair | ( | int | nSpaceOffset, |
| bool | bOffsetRegular = true, |
||
| bool | bNewline = true |
||
| ) |
Definition at line 202 of file CKeyValuePair.cpp.
| void CKeyValuePair::printSpaces | ( | int | nSpaces | ) |
Definition at line 350 of file CKeyValuePair.cpp.
| bool CKeyValuePair::removeChildForKey | ( | string | strKey | ) |
Definition at line 541 of file CKeyValuePair.cpp.
| vector< designator_integration_msgs::KeyValuePair > CKeyValuePair::serializeToMessage | ( | int | nParent, |
| int | nID | ||
| ) |
Definition at line 478 of file CKeyValuePair.cpp.
| void CKeyValuePair::setActionDesignatorDescription | ( | string | strKey, |
| list< CKeyValuePair * > | lstDescription | ||
| ) |
Definition at line 427 of file CKeyValuePair.cpp.
| void CKeyValuePair::setChildren | ( | list< CKeyValuePair * > | lstChildren | ) |
Definition at line 198 of file CKeyValuePair.cpp.
| void CKeyValuePair::setID | ( | int | nID | ) |
Definition at line 356 of file CKeyValuePair.cpp.
| void CKeyValuePair::setKey | ( | string | strKey | ) |
Definition at line 435 of file CKeyValuePair.cpp.
| void CKeyValuePair::setLocationDesignatorDescription | ( | string | strKey, |
| enum ValueType | evtType, | ||
| list< CKeyValuePair * > | lstDescription | ||
| ) |
Definition at line 423 of file CKeyValuePair.cpp.
| void CKeyValuePair::setObjectDesignatorDescription | ( | string | strKey, |
| list< CKeyValuePair * > | lstDescription | ||
| ) |
Definition at line 431 of file CKeyValuePair.cpp.
| void CKeyValuePair::setParent | ( | int | nParent | ) |
Definition at line 360 of file CKeyValuePair.cpp.
| void CKeyValuePair::setType | ( | enum ValueType | evtType | ) |
Definition at line 439 of file CKeyValuePair.cpp.
| void CKeyValuePair::setValue | ( | string | strValue | ) |
Definition at line 364 of file CKeyValuePair.cpp.
| void CKeyValuePair::setValue | ( | float | fValue | ) |
Definition at line 369 of file CKeyValuePair.cpp.
| void CKeyValuePair::setValue | ( | geometry_msgs::PoseStamped | psPoseStampedValue | ) |
Definition at line 374 of file CKeyValuePair.cpp.
| void CKeyValuePair::setValue | ( | geometry_msgs::Pose | psPoseValue | ) |
Definition at line 379 of file CKeyValuePair.cpp.
| void CKeyValuePair::setValue | ( | void * | vdValue, |
| unsigned int | unLength | ||
| ) |
Definition at line 392 of file CKeyValuePair.cpp.
| void CKeyValuePair::setValue | ( | enum ValueType | evtType, |
| list< CKeyValuePair * > | lstDescription | ||
| ) |
Definition at line 411 of file CKeyValuePair.cpp.
| void CKeyValuePair::setValue | ( | string | strKey, |
| string | strValue | ||
| ) |
Definition at line 595 of file CKeyValuePair.cpp.
| void CKeyValuePair::setValue | ( | string | strKey, |
| float | fValue | ||
| ) |
Definition at line 605 of file CKeyValuePair.cpp.
| void CKeyValuePair::setValue | ( | string | strKey, |
| geometry_msgs::PoseStamped | psPoseStampedValue | ||
| ) |
Definition at line 615 of file CKeyValuePair.cpp.
| void CKeyValuePair::setValue | ( | string | strKey, |
| geometry_msgs::Pose | psPoseValue | ||
| ) |
Definition at line 625 of file CKeyValuePair.cpp.
| void CKeyValuePair::setValue | ( | string | strKey, |
| char * | acValue, | ||
| int | nLength | ||
| ) |
| void CKeyValuePair::setValue | ( | string | strKey, |
| enum ValueType | evtType, | ||
| list< CKeyValuePair * > | lstDescription | ||
| ) |
Definition at line 401 of file CKeyValuePair.cpp.
| string CKeyValuePair::stringValue | ( | ) |
Definition at line 91 of file CKeyValuePair.cpp.
| string CKeyValuePair::stringValue | ( | string | strChildKey | ) |
Definition at line 553 of file CKeyValuePair.cpp.
| enum ValueType CKeyValuePair::type | ( | ) |
Reimplemented in CDesignator.
Definition at line 87 of file CKeyValuePair.cpp.
char* CKeyValuePair::m_acValue [private] |
Definition at line 36 of file CKeyValuePair.h.
enum ValueType CKeyValuePair::m_evtType [protected] |
Definition at line 42 of file CKeyValuePair.h.
double CKeyValuePair::m_fValue [private] |
Definition at line 35 of file CKeyValuePair.h.
list<CKeyValuePair*> CKeyValuePair::m_lstChildren [protected] |
Definition at line 43 of file CKeyValuePair.h.
int CKeyValuePair::m_nID [private] |
Definition at line 31 of file CKeyValuePair.h.
int CKeyValuePair::m_nParent [private] |
Definition at line 32 of file CKeyValuePair.h.
geometry_msgs::Pose CKeyValuePair::m_posPoseValue [private] |
Definition at line 38 of file CKeyValuePair.h.
geometry_msgs::PoseStamped CKeyValuePair::m_psPoseStampedValue [private] |
Definition at line 39 of file CKeyValuePair.h.
string CKeyValuePair::m_strKey [private] |
Definition at line 33 of file CKeyValuePair.h.
string CKeyValuePair::m_strValue [private] |
Definition at line 34 of file CKeyValuePair.h.
unsigned int CKeyValuePair::m_unValueLength [private] |
Definition at line 37 of file CKeyValuePair.h.