MTDataTypes.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2010, ISR University of Coimbra.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the ISR University of Coimbra nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Gonçalo Cabrita
00036 * Notes: Original code in Cocoa from 07/08/2009, went C++ on 10/11/2010
00037 *********************************************************************/
00038 
00039 // MTComm message
00040 // PRE BID MID LEN DATA CHECKSUM
00041 
00042 //Extended MTComm message
00043 // PRE BID MID LEN EXT_LEN DATA CHECKSUM
00044 
00045 namespace Xsens
00046 {
00047         typedef enum _MTMessageIdentifier {
00048         
00049                 // WakeUp + State messages
00050                 WakeUp = 62,
00051                 WakeUpAck = 63,
00052                 GoToConfig = 48,
00053                 GoToConfigAck = 49,
00054                 GoToMeasurement = 16,
00055                 GoToMeasurementAck = 17,
00056                 Reset = 64,
00057                 ResetAck = 65,
00058         
00059                 // Informational messages
00060                 ReqDID = 0,
00061                 DeviceID = 1,
00062                 InitMT = 2,
00063                 InitMTResults = 3,
00064                 ReqProductCode = 28,
00065                 ProductCode = 29,
00066                 ReqFWRev = 18,
00067                 FirmwareRev = 19,
00068                 ReqDataLength = 10,
00069                 DataLength = 11,
00070                 Error = 66,
00071                 ReqGPSStatus = 166,                             // Only supported by MTi-G
00072                 GPSStatus = 167,                                // Only supported by MTi-G
00073         
00074                 // Device-specific messages
00075                 ReqBaurate = 24,
00076                 ReqBaurateAck = 25,
00077                 SetBaudrate = 24,
00078                 SeqBaurateAck = 25,
00079                 ReqErrorMode = 218,
00080                 ReqErrorModeAck = 219,
00081                 SetErrorMode = 218,
00082                 SetErrorModeAck = 219,
00083                 ReqLocationID = 132,
00084                 ReqLocationIDAck = 133,
00085                 SetLocationID = 132,
00086                 SetLocationIDAck = 133,
00087                 RestoreFactoryDef = 14,
00088                 RestoreFactoryDefAck = 15,
00089                 ReqTransmitDelay = 220,
00090                 ReqTransmitDelayAck = 221,
00091                 SetTransmitDelay = 220,
00092                 SetTransmitDelayAck = 221,
00093         
00094                 // Synchronization messages
00095                 ReqSyncInSettings = 214,
00096                 ReqSyncInSettingsAck = 215,
00097                 SetSyncInSettings = 214,
00098                 SetSyncInSettingsAck = 215,
00099                 ReqSyncOutSettings = 216,
00100                 ReqSyncOutSettingsAck = 217,
00101                 SetSyncOutSettings = 216,
00102                 SetSyncOutSettingsAck = 217,
00103         
00104                 // Configuration messages
00105                 ReqConfiguration = 12,
00106                 Configuration = 13,
00107                 ReqPeriod = 4,
00108                 ReqPeriodAck = 5,
00109                 SetPeriod = 4,
00110                 SetPeriodAck = 5,
00111                 ReqOutputSkipFactor = 212,
00112                 ReqOutputSkipFactorAck = 213,
00113                 SetOutputSkipFactor = 212,
00114                 SetOutputSkipFactorAck = 213,
00115                 ReqObjectAlignment = 224,
00116                 ReqObjectAlignmentAck = 225,
00117                 SetObjectAlignment = 224,
00118                 SetObjectAlignmentAck = 225,
00119                 ReqOutputMode = 208,
00120                 ReqOutputModeAck = 209,
00121                 SetOutputMode = 208,
00122                 SetOutputModeAck = 209,
00123                 ReqOutputSettings = 210,
00124                 ReqOutputSettingsAck = 211,
00125                 SetOutputSettings = 210,
00126                 SetOutputSettingsAck = 211,
00127         
00128                 // Data-related messages
00129                 ReqData = 52,
00130                 MTData = 50,
00131         
00132                 // XKF Filter messages
00133                 ReqHeading = 130,
00134                 ReqHeadingAck = 131,
00135                 SetHeading = 130,
00136                 SetHeadingAck = 131,
00137                 ResetOrientation = 164,
00138                 ResetOrientationAck = 165,
00139                 ReqUTCTime = 96,                                        // Only supported by MTi-G
00140                 UTCTime = 97,                                           // Only supported by MTi-G
00141                 ReqMagneticDeclination = 106,
00142                 ReqMagneticDeclinationAck = 107,
00143                 SetMagneticDeclination = 106,
00144                 SetMagneticDeclinationAck = 107,
00145                 ReqAvailableScenarios = 98,
00146                 AvailableScenarios = 99,
00147                 ReqCurrentScenario = 100,
00148                 ReqCurrentScenarioAck = 101,
00149                 SetCurrentScenario = 100,
00150                 SetCurrentScenarioAck = 101,
00151                 ReqGravityMagnitude = 102,
00152                 ReqGravityMagnitudeAck = 103,
00153                 SetGravityMagnitude = 102,
00154                 SetGravityMagnitudeAck = 103,
00155                 ReqProcessingFlags = 32,
00156                 ReqProcessingFlagsAck = 33,
00157                 SetProcessingFlags = 32,
00158                 SetProcessingFlagsAck = 33,
00159                 ReqLeverArmGps = 104,
00160                 ReqLeverArmGpsAck = 105,
00161                 SetLeverArmGps = 104,
00162                 SetLeverArmGpsAck = 105,
00163                 SetNoRotation = 34,
00164                 SetNoRotationAck = 35,
00165                 
00166         } MTMessageIdentifier;
00167 
00168         typedef enum _MTOrientationMode {
00169         
00170                 Quaternion = 0,
00171                 EulerAngles = 1,
00172                 Matrix = 2,
00173         
00174         } MTOrientationMode;
00175 }
00176 
00177 // EOF
00178 
00179 


lse_xsens_mti
Author(s): Gonçalo Cabrita, Nicolas Vignard
autogenerated on Mon Jan 6 2014 11:28:04