$search
00001 //================================================================================================= 00002 // Copyright (c) 2011, Johannes Meyer and Martin Nowara, TU Darmstadt 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 // * Redistributions of source code must retain the above copyright 00008 // notice, this list of conditions and the following disclaimer. 00009 // * Redistributions in binary form must reproduce the above copyright 00010 // notice, this list of conditions and the following disclaimer in the 00011 // documentation and/or other materials provided with the distribution. 00012 // * Neither the name of the Flight Systems and Automatic Control group, 00013 // TU Darmstadt, nor the names of its contributors may be used to 00014 // endorse or promote products derived from this software without 00015 // specific prior written permission. 00016 00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00027 //================================================================================================= 00028 00029 #ifndef HECTOR_POSE_ESTIMATION_TYPES_H 00030 #define HECTOR_POSE_ESTIMATION_TYPES_H 00031 00032 #include <hector_pose_estimation/matrix.h> 00033 00034 // Use system model with angular rates. 00035 // #define USE_RATE_SYSTEM_MODEL 00036 00037 namespace hector_pose_estimation { 00038 00039 enum StateIndex { 00040 QUATERNION_W = 1, 00041 QUATERNION_X, 00042 QUATERNION_Y, 00043 QUATERNION_Z, 00044 #ifdef USE_RATE_SYSTEM_MODEL 00045 RATE_X, 00046 RATE_Y, 00047 RATE_Z, 00048 #endif // USE_RATE_SYSTEM_MODEL 00049 POSITION_X, 00050 POSITION_Y, 00051 POSITION_Z, 00052 VELOCITY_X, 00053 VELOCITY_Y, 00054 VELOCITY_Z, 00055 BIAS_ACCEL_X, 00056 BIAS_ACCEL_Y, 00057 BIAS_ACCEL_Z, 00058 BIAS_GYRO_X, 00059 BIAS_GYRO_Y, 00060 BIAS_GYRO_Z, 00061 }; 00062 static const unsigned int StateDimension = BIAS_GYRO_Z; 00063 typedef ColumnVector_<StateDimension> StateVector; 00064 typedef SymmetricMatrix_<StateDimension> StateCovariance; 00065 00066 enum { 00067 STATE_ALIGNMENT = 1, 00068 STATE_DEGRADED = 2, 00069 STATE_READY = 4, 00070 00071 STATE_ROLLPITCH = 8, 00072 STATE_YAW = 16, 00073 STATE_XY_VELOCITY = 32, 00074 STATE_XY_POSITION = 64, 00075 STATE_Z_VELOCITY = 128, 00076 STATE_Z_POSITION = 256, 00077 00078 STATE_ALL = -1 00079 }; 00080 typedef unsigned int SystemStatus; 00081 00082 static const char* const SystemStatusStrings[] = { 00083 "ALIGNMENT", "DEGRADED", "READY", "ROLLPITCH", "YAW", "XY_VELOCITY", "XY_POSITION", "Z_VELOCITY", "Z_POSITION" 00084 }; 00085 std::string getSystemStatusString(const SystemStatus& status); 00086 static inline std::ostream& operator<<(std::ostream& os, const SystemStatus& status) { 00087 return os << getSystemStatusString(status); 00088 } 00089 00090 } // namespace hector_pose_estimation 00091 00092 #endif // HECTOR_POSE_ESTIMATION_TYPES_H