Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef _DATABASE_HELPER_CLASSES_H_
00038 #define _DATABASE_HELPER_CLASSES_H_
00039
00040 #include <database_interface/db_class.h>
00041 #include <geometry_msgs/Pose.h>
00042
00043 namespace database_interface {
00044
00046 template <>
00047 class DBField< std::vector<float> > : public DBFieldData< std::vector<float> >
00048 {
00049 public:
00050 DBField(Type type, DBClass *owner, std::string name, std::string table_name, bool write_permission) :
00051 DBFieldData< std::vector<float> >(type, owner, name, table_name, write_permission) {}
00052
00053 DBField(DBClass *owner, const DBField< std::vector<float> > *other) :
00054 DBFieldData< std::vector<float> >(owner, other)
00055 {
00056 this->copy(other);
00057 }
00058
00059 virtual bool fromBinary(const char* binary, size_t length)
00060 {
00061
00062 if (!length)
00063 {
00064 data_.clear();
00065 return true;
00066 }
00067
00068 if ( length % sizeof(float) != 0)
00069 {
00070 std::cerr << "Binary conversion of " << length << " bytes to vector<float> failed\n";
00071 return false;
00072 }
00073 data_.resize(length / sizeof(float));
00074 memcpy(&(data_[0]), binary, length);
00075 return true;
00076 }
00077
00078 virtual bool toBinary(const char* &binary, size_t &length) const
00079 {
00080 length = sizeof(float) * data_.size();
00081 if (!data_.empty())
00082 {
00083 binary = reinterpret_cast<const char*>(&(data_[0]));
00084 }
00085 return true;
00086 }
00087 };
00088
00090 template <>
00091 class DBField< std::vector<uint8_t> > : public DBFieldData< std::vector<uint8_t> >
00092 {
00093 public:
00094 DBField(Type type, DBClass *owner, std::string name, std::string table_name, bool write_permission) :
00095 DBFieldData< std::vector<uint8_t> >(type, owner, name, table_name, write_permission) {}
00096
00097 DBField(DBClass *owner, const DBField< std::vector<uint8_t> > *other) :
00098 DBFieldData< std::vector<uint8_t> >(owner, other)
00099 {
00100 this->copy(other);
00101 }
00102
00103 virtual bool fromBinary(const char* binary, size_t length)
00104 {
00105
00106 if (!length)
00107 {
00108 data_.clear();
00109 return true;
00110 }
00111
00112 if ( length % sizeof(uint8_t) != 0)
00113 {
00114 std::cerr << "Binary conversion of " << length << " bytes to vector<uint8_t> failed\n";
00115 return false;
00116 }
00117 data_.resize(length / sizeof(uint8_t));
00118 memcpy(&(data_[0]), binary, length);
00119 return true;
00120 }
00121
00122 virtual bool toBinary(const char* &binary, size_t &length) const
00123 {
00124 length = sizeof(uint8_t) * data_.size();
00125 if (!data_.empty())
00126 {
00127 binary = reinterpret_cast<const char*>(&(data_[0]));
00128 }
00129 return true;
00130 }
00131 };
00132
00133
00134
00135
00136 }
00137
00138 namespace household_objects_database {
00139
00140
00141
00142
00143
00144
00145
00146
00147
00148
00149
00151
00154 class DatabasePose
00155 {
00156 public:
00157 geometry_msgs::Pose pose_;
00158 };
00159
00160 std::istream& operator >> (std::istream &str, DatabasePose &dhp);
00161 std::ostream& operator << (std::ostream &str, const DatabasePose &dhp);
00162
00164
00167 class DatabaseHandPosture
00168 {
00169 public:
00170 std::vector<double> joint_angles_;
00171 };
00172
00173 std::istream& operator >> (std::istream &str, DatabaseHandPosture &dhp);
00174 std::ostream& operator << (std::ostream &str, const DatabaseHandPosture &dhp);
00175
00176 }
00177
00178 #endif