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 #ifndef VSSPDEFS_H
00031 #define VSSPDEFS_H
00032
00033 #include <cstdint>
00034 #include <cmath>
00035
00036 namespace vssp
00037 {
00038
00039 static const uint32_t VSSP_MARK = ('V' << 0) | ('S' << 8) | ('S' << 16) | ('P' << 24);
00040 static const uint32_t STATUS_OK = ('0' << 0) | ('0' << 8) | ('0' << 16) | (0xA << 24);
00041 static const uint32_t STATUS_COMMAND_UNKNOWN = ('1' << 0) | ('0' << 8) | ('1' << 16) | (0xA << 24);
00042 static const uint32_t STATUS_COMMAND_INVALID = ('1' << 0) | ('0' << 8) | ('2' << 16) | (0xA << 24);
00043 static const uint32_t STATUS_COMMAND_INVALUD_METHOD = ('1' << 0) | ('0' << 8) | ('3' << 16) | (0xA << 24);
00044 static const uint32_t STATUS_COMMAND_OUT_OF_RANGE = ('1' << 0) | ('0' << 8) | ('4' << 16) | (0xA << 24);
00045 static const uint32_t STATUS_COMMUNICATION_FAILURE = ('2' << 0) | ('0' << 8) | ('1' << 16) | (0xA << 24);
00046 static const uint32_t STATUS_UNKNOWN_ERROR = ('3' << 0) | ('0' << 8) | ('1' << 16) | (0xA << 24);
00047
00048 static const uint32_t TYPE_GET = ('G' << 0) | ('E' << 8) | ('T' << 16) | (':' << 24);
00049 static const uint32_t TYPE_SET = ('S' << 0) | ('E' << 8) | ('T' << 16) | (':' << 24);
00050 static const uint32_t TYPE_DAT = ('D' << 0) | ('A' << 8) | ('T' << 16) | (':' << 24);
00051 static const uint32_t TYPE_VER = ('V' << 0) | ('E' << 8) | ('R' << 16) | (':' << 24);
00052 static const uint32_t TYPE_PNG = ('P' << 0) | ('N' << 8) | ('G' << 16) | (':' << 24);
00053 static const uint32_t TYPE_ERR = ('E' << 0) | ('R' << 8) | ('R' << 16) | (':' << 24);
00054 static const uint32_t TYPE_RI = ('_' << 0) | ('r' << 8) | ('i' << 16) | (':' << 24);
00055 static const uint32_t TYPE_RO = ('_' << 0) | ('r' << 8) | ('o' << 16) | (':' << 24);
00056 static const uint32_t TYPE_AX = ('_' << 0) | ('a' << 8) | ('x' << 16) | (':' << 24);
00057 static const uint32_t TYPE_ER = ('_' << 0) | ('e' << 8) | ('r' << 16) | (':' << 24);
00058
00059 enum AuxId
00060 {
00061 AX_MASK_ANGVEL_X = 31,
00062 AX_MASK_ANGVEL_Y = 30,
00063 AX_MASK_ANGVEL_Z = 29,
00064 AX_MASK_LINACC_X = 28,
00065 AX_MASK_LINACC_Y = 27,
00066 AX_MASK_LINACC_Z = 26,
00067 AX_MASK_MAG_X = 25,
00068 AX_MASK_MAG_Y = 24,
00069 AX_MASK_MAG_Z = 23,
00070 AX_MASK_TEMP = 22,
00071 AX_MASK_FIRST = 22,
00072 AX_MASK_LAST = 31
00073 };
00074 static const uint32_t AX_MASK_ANGVEL = (1 << AX_MASK_ANGVEL_X) | (1 << AX_MASK_ANGVEL_Y) | (1 << AX_MASK_ANGVEL_Z);
00075 static const uint32_t AX_MASK_LINACC = (1 << AX_MASK_LINACC_X) | (1 << AX_MASK_LINACC_Y) | (1 << AX_MASK_LINACC_Z);
00076 static const uint32_t AX_MASK_MAG = (1 << AX_MASK_MAG_X) | (1 << AX_MASK_MAG_Y) | (1 << AX_MASK_MAG_Z);
00077
00078 #pragma pack(push, 1)
00079 struct Header
00080 {
00081 uint32_t mark;
00082 uint32_t type;
00083 uint32_t status;
00084 uint16_t header_length;
00085 uint16_t length;
00086 uint32_t received_time_ms;
00087 uint32_t send_time_ms;
00088 };
00089 struct RangeHeader
00090 {
00091 uint16_t header_length;
00092 uint32_t line_head_timestamp_ms;
00093 uint32_t line_tail_timestamp_ms;
00094 int16_t line_head_h_angle_ratio;
00095 int16_t line_tail_h_angle_ratio;
00096 uint8_t frame;
00097 uint8_t field;
00098 uint16_t line;
00099 uint16_t spot;
00100 };
00101 struct RangeIndex
00102 {
00103 uint16_t index_length;
00104 uint16_t nspots;
00105 };
00106 struct DataRangeIntensity
00107 {
00108 uint16_t range_mm;
00109 uint16_t intensity;
00110 };
00111 struct DataRangeOnly
00112 {
00113 uint16_t range_mm;
00114 };
00115 struct AuxHeader
00116 {
00117 uint16_t header_length;
00118 uint32_t timestamp_ms;
00119 uint32_t data_bitfield;
00120 uint8_t data_count;
00121 uint8_t data_ms;
00122 };
00123 struct AuxData
00124 {
00125 int32_t val;
00126 };
00127 #pragma pack(pop)
00128
00129 class AuxFactorArray
00130 {
00131 public:
00132 double operator[](AuxId id) const
00133 {
00134 return k_[static_cast<int>(id)];
00135 };
00136 double k_[AX_MASK_LAST + 1];
00137 };
00138 struct TableSincos
00139 {
00140 double s;
00141 double c;
00142 };
00143 struct XYZ
00144 {
00145 double x;
00146 double y;
00147 double z;
00148 };
00149 class XYZI
00150 {
00151 public:
00152 double x;
00153 double y;
00154 double z;
00155 double i;
00156 double r;
00157
00158 XYZI()
00159 {
00160 }
00161 XYZI(const double &v_sin, const double &v_cos, const double &h_sin, const double &h_cos)
00162 {
00163 i = 0;
00164 r = 0;
00165 x = v_cos * h_cos;
00166 y = v_cos * h_sin;
00167 z = v_sin;
00168 }
00169 XYZI operator*(const DataRangeIntensity &data) const
00170 {
00171 XYZI ret = *this;
00172 double r = data.range_mm * 0.001;
00173 ret.i = data.intensity;
00174 ret.x *= r;
00175 ret.y *= r;
00176 ret.z *= r;
00177 ret.r = r;
00178 return ret;
00179 }
00180 XYZI operator*(const DataRangeOnly &data) const
00181 {
00182 XYZI ret = *this;
00183 double r = data.range_mm * 0.001;
00184 ret.i = 0;
00185 ret.x *= r;
00186 ret.y *= r;
00187 ret.z *= r;
00188 ret.r = r;
00189 return *this;
00190 }
00191 };
00192 class Aux
00193 {
00194 public:
00195 XYZ ang_vel;
00196 XYZ lin_acc;
00197 XYZ mag;
00198 double temp;
00199
00200 Aux()
00201 {
00202 ang_vel.x = ang_vel.y = ang_vel.z = 0.0;
00203 lin_acc.x = lin_acc.y = lin_acc.z = 0.0;
00204 mag.x = mag.y = mag.z = 0.0;
00205 temp = 0.0;
00206 }
00207 double operator[](AuxId id) const
00208 {
00209 return operator[](id);
00210 }
00211 double &operator[](AuxId id)
00212 {
00213 switch (id)
00214 {
00215 case vssp::AX_MASK_ANGVEL_X:
00216 return ang_vel.x;
00217 case vssp::AX_MASK_ANGVEL_Y:
00218 return ang_vel.y;
00219 case vssp::AX_MASK_ANGVEL_Z:
00220 return ang_vel.z;
00221 case vssp::AX_MASK_LINACC_X:
00222 return lin_acc.x;
00223 case vssp::AX_MASK_LINACC_Y:
00224 return lin_acc.y;
00225 case vssp::AX_MASK_LINACC_Z:
00226 return lin_acc.z;
00227 case vssp::AX_MASK_MAG_X:
00228 return mag.x;
00229 case vssp::AX_MASK_MAG_Y:
00230 return mag.y;
00231 case vssp::AX_MASK_MAG_Z:
00232 return mag.z;
00233 case vssp::AX_MASK_TEMP:
00234 return temp;
00235 }
00236 throw "Invalid AUX data id";
00237 }
00238 };
00239
00240 static const double G = 9.807;
00241 static const double DEG = (M_PI / 180.0);
00242
00243
00244
00245
00246 static const AuxFactorArray AUX_FACTOR_DEFAULT =
00247 {
00248 {
00249 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0,
00250 1.0,
00251 0.6e-6, 0.6e-6, 0.6e-6,
00252 G / 8192.0, G / 8192.0, G / 8192.0,
00253 DEG / 131.0, DEG / 131.0, DEG / 131.0
00254 }
00255 };
00256
00257 }
00258
00259 #endif // VSSPDEFS_H