vsspdefs.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2014, ATR, Atsushi Watanabe
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
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 RangeHeaderV2R1
00102 {
00103   uint8_t vertical_field;
00104   uint8_t vertical_interlace;
00105 };
00106 const RangeHeaderV2R1 RANGE_HEADER_V2R1_DEFAULT =
00107     {
00108       0, 1
00109     };
00110 struct RangeIndex
00111 {
00112   uint16_t index_length;
00113   uint16_t nspots;
00114 };
00115 struct DataRangeIntensity
00116 {
00117   uint16_t range_mm;
00118   uint16_t intensity;
00119 };
00120 struct DataRangeOnly
00121 {
00122   uint16_t range_mm;
00123 };
00124 struct AuxHeader
00125 {
00126   uint16_t header_length;
00127   uint32_t timestamp_ms;
00128   uint32_t data_bitfield;
00129   uint8_t data_count;
00130   uint8_t data_ms;
00131 };
00132 struct AuxData
00133 {
00134   int32_t val;
00135 };
00136 #pragma pack(pop)
00137 
00138 class AuxFactorArray
00139 {
00140 public:
00141   double operator[](AuxId id) const
00142   {
00143     return k_[static_cast<int>(id)];
00144   }
00145   double k_[AX_MASK_LAST + 1];
00146 };
00147 struct TableSincos
00148 {
00149   double s;
00150   double c;
00151 };
00152 struct XYZ
00153 {
00154   double x;
00155   double y;
00156   double z;
00157 };
00158 class XYZI
00159 {
00160 public:
00161   double x;
00162   double y;
00163   double z;
00164   double i;
00165   double r;
00166 
00167   XYZI()
00168   {
00169   }
00170   XYZI(const double &v_sin, const double &v_cos, const double &h_sin, const double &h_cos)
00171   {
00172     i = 0;
00173     r = 0;
00174     x = v_cos * h_cos;
00175     y = v_cos * h_sin;
00176     z = v_sin;
00177   }
00178   XYZI operator*(const DataRangeIntensity &data) const
00179   {
00180     XYZI ret = *this;
00181     double r = data.range_mm * 0.001;
00182     ret.i = data.intensity;
00183     ret.x *= r;
00184     ret.y *= r;
00185     ret.z *= r;
00186     ret.r = r;
00187     return ret;
00188   }
00189   XYZI operator*(const DataRangeOnly &data) const
00190   {
00191     XYZI ret = *this;
00192     double r = data.range_mm * 0.001;
00193     ret.i = 0;
00194     ret.x *= r;
00195     ret.y *= r;
00196     ret.z *= r;
00197     ret.r = r;
00198     return *this;
00199   }
00200 };
00201 class Aux
00202 {
00203 public:
00204   XYZ ang_vel;
00205   XYZ lin_acc;
00206   XYZ mag;
00207   double temp;
00208 
00209   Aux()
00210   {
00211     ang_vel.x = ang_vel.y = ang_vel.z = 0.0;
00212     lin_acc.x = lin_acc.y = lin_acc.z = 0.0;
00213     mag.x = mag.y = mag.z = 0.0;
00214     temp = 0.0;
00215   }
00216   double operator[](AuxId id) const
00217   {
00218     return operator[](id);
00219   }
00220   double &operator[](AuxId id)
00221   {
00222     switch (id)
00223     {
00224       case vssp::AX_MASK_ANGVEL_X:
00225         return ang_vel.x;
00226       case vssp::AX_MASK_ANGVEL_Y:
00227         return ang_vel.y;
00228       case vssp::AX_MASK_ANGVEL_Z:
00229         return ang_vel.z;
00230       case vssp::AX_MASK_LINACC_X:
00231         return lin_acc.x;
00232       case vssp::AX_MASK_LINACC_Y:
00233         return lin_acc.y;
00234       case vssp::AX_MASK_LINACC_Z:
00235         return lin_acc.z;
00236       case vssp::AX_MASK_MAG_X:
00237         return mag.x;
00238       case vssp::AX_MASK_MAG_Y:
00239         return mag.y;
00240       case vssp::AX_MASK_MAG_Z:
00241         return mag.z;
00242       case vssp::AX_MASK_TEMP:
00243         return temp;
00244     }
00245     throw "Invalid AUX data id";
00246   }
00247 };
00248 
00249 static const double G = 9.807;
00250 static const double DEG = (M_PI / 180.0);
00251 
00252 // Default value of Aux data scaling factor
00253 // note: there is no way to get these values in communication
00254 //      with prototype edition of the HOKUYO 3D sensor
00255 static const AuxFactorArray AUX_FACTOR_DEFAULT =
00256     {
00257       {
00258         1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0,
00259         1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0,
00260         1.0, 1.0, 1.0, 1.0, 1.0, 1.0,
00261         1.0,                                 // Temperature [?]
00262         0.6e-6, 0.6e-6, 0.6e-6,              // Magnetometer [T]
00263         G / 8192.0, G / 8192.0, G / 8192.0,  // Accelerometer [m/ss]
00264         DEG / 65.5, DEG / 65.5, DEG / 65.5   // Gyrometer [rad/s]
00265       }
00266     };
00267 
00268 }  // namespace vssp
00269 
00270 #endif  // VSSPDEFS_H


hokuyo3d
Author(s): Atsushi Watanabe
autogenerated on Thu Jun 6 2019 20:08:29