dispatch.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015-2017, Dataspeed Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Dataspeed Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #ifndef _DISPATCH_H
00036 #define _DISPATCH_H
00037 #include <stdint.h>
00038 
00039 #pragma pack(push, 1)
00040 typedef union {
00041   uint8_t bytes[8];
00042   struct {
00043     uint32_t gps_minutes;
00044     uint8_t num_sats;
00045     uint8_t position_mode;
00046     uint8_t velocity_mode;
00047     uint8_t orientation_mode;
00048   } chan0;
00049   struct {
00050     uint16_t acc_position_north; // 1e-3 m
00051     uint16_t acc_position_east;
00052     uint16_t acc_position_down;
00053     uint8_t age;
00054   } chan3;
00055   struct {
00056     uint16_t acc_velocity_north; // 1e-3 m/s
00057     uint16_t acc_velocity_east;
00058     uint16_t acc_velocity_down;
00059     uint8_t age;
00060   } chan4;
00061   struct {
00062     uint16_t acc_heading; // 1e-5 rad
00063     uint16_t acc_pitch;
00064     uint16_t acc_roll;
00065     uint8_t age;
00066   } chan5;
00067   struct {
00068     int16_t base_station_age;
00069     int8_t base_station_id[4];
00070   } chan20;
00071   struct {
00072     uint16_t delay_ms;
00073   } chan23;
00074   struct {
00075     uint8_t heading_quality; // 0:None 1:Poor 2:RTK Float 3:RTK Integer
00076   } chan27;
00077   struct {
00078     int16_t heading_misalignment_angle; // 1e-4 rad
00079     uint16_t heading_misalignment_accuracy; // 1e-4 rad
00080     uint16_t :16;
00081     uint8_t valid;
00082   } chan37;
00083   struct {
00084     int16_t undulation; // 5e-3 m
00085     uint8_t HDOP; // 1e-1
00086     uint8_t PDOP; // 1e-1
00087   } chan48;
00088 } Channel;
00089 typedef struct {
00090   uint8_t sync;
00091   uint16_t time;
00092   int32_t accel_x :24; // 1e-4 m/s^2
00093   int32_t accel_y :24; // 1e-4 m/s^2
00094   int32_t accel_z :24; // 1e-4 m/s^2
00095   int32_t gyro_x :24; // 1e-5 rad/s
00096   int32_t gyro_y :24; // 1e-5 rad/s
00097   int32_t gyro_z :24; // 1e-5 rad/s
00098   uint8_t nav_status;
00099   uint8_t chksum1;
00100   double latitude;
00101   double longitude;
00102   float altitude;
00103   int32_t vel_north :24; // 1e-4 m/s
00104   int32_t vel_east :24; // 1e-4 m/s
00105   int32_t vel_down :24; // 1e-4 m/s
00106   int32_t heading :24; // 1e-6 rad
00107   int32_t pitch :24; // 1e-6 rad
00108   int32_t roll :24; // 1e-6 rad
00109   uint8_t chksum2;
00110   uint8_t channel;
00111   Channel chan;
00112   uint8_t chksum3;
00113 } Packet;
00114 enum {
00115   MODE_NONE = 0,
00116   MODE_SEARCH = 1,
00117   MODE_DOPPLER = 2,
00118   MODE_SPS = 3,
00119   MODE_DIFFERENTIAL = 4,
00120   MODE_RTK_FLOAT = 5,
00121   MODE_RTK_INTEGER = 6,
00122   MODE_WAAS = 7,
00123   MODE_OMNISTAR_VBS = 8,
00124   MODE_OMNISTAR_HP = 9,
00125   MODE_NO_DATA = 10,
00126   MODE_BLANKED = 11,
00127   MODE_DOPPLER_PP = 12,
00128   MODE_SPS_PP = 13,
00129   MODE_DIFFERENTIAL_PP = 14,
00130   MODE_RTK_FLOAT_PP = 15,
00131   MODE_RTK_INTEGER_PP = 16,
00132   MODE_OMNISTAR_XP = 17,
00133   MODE_CDGPS = 18,
00134   MODE_NOT_RECOGNISED = 19,
00135   MODE_DOPPLER_GX = 20,
00136   MODE_SPS_GX = 21,
00137   MODE_DIFFERENTIAL_GX = 22,
00138   MODE_RTK_FLOAT_GX = 23,
00139   MODE_RTK_INTEGER_GX = 24,
00140   MODE_DOPPLER_IX = 25,
00141   MODE_SPS_IX = 26,
00142   MODE_DIFFERENTIAL_IX = 27,
00143   MODE_RTK_FLOAT_IX = 28,
00144   MODE_RTK_INTEGER_IX = 29,
00145   MODE_PPP_CONVERGING = 30,
00146   MODE_PPP = 31,
00147   MODE_UNKNOWN = 32
00148 };
00149 #pragma pack(pop)
00150 
00151 static bool validatePacket(const Packet *packet) {
00152   if (packet->sync == 0xE7) {
00153     const uint8_t *ptr = (uint8_t*)packet;
00154     uint8_t chksum = 0;
00155     for (unsigned int i = 1; i < sizeof(Packet) - 1; i++) {
00156       chksum += ptr[i];
00157     }
00158     return chksum == packet->chksum3;
00159   }
00160   return false;
00161 }
00162 
00163 #define BUILD_ASSERT(cond) do { (void) sizeof(char [1 - 2*!(cond)]); } while(0)
00164 static void dispatchAssertSizes() {
00165   BUILD_ASSERT(8 == sizeof(Channel));
00166   BUILD_ASSERT(72 == sizeof(Packet));
00167 }
00168 #undef BUILD_ASSERT
00169 
00170 #endif // _DISPATCH_H


oxford_gps_eth
Author(s): Kevin Hallenbeck
autogenerated on Wed Jul 10 2019 03:30:07