00001 //================================================================================================= 00002 // Copyright (c) 2011, Johannes Meyer, 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_GPS_H 00030 #define HECTOR_POSE_ESTIMATION_GPS_H 00031 00032 #include <hector_pose_estimation/measurement.h> 00033 #include <hector_pose_estimation/global_reference.h> 00034 00035 namespace hector_pose_estimation { 00036 00037 class GPSModel : public MeasurementModel_<GPSModel,4> { 00038 public: 00039 GPSModel(); 00040 virtual ~GPSModel(); 00041 00042 virtual SystemStatus getStatusFlags() { return STATE_POSITION_XY | STATE_VELOCITY_XY; } 00043 00044 virtual bool prepareUpdate(State &state, const MeasurementUpdate &update); 00045 00046 virtual void getMeasurementNoise(NoiseVariance& R, const State&, bool init); 00047 virtual void getExpectedValue(MeasurementVector& y_pred, const State& state); 00048 virtual void getStateJacobian(MeasurementMatrix& C, const State& state, bool init); 00049 00050 protected: 00051 double position_stddev_; 00052 double velocity_stddev_; 00053 State::RotationMatrix R; 00054 }; 00055 00056 struct GPSUpdate : public MeasurementUpdate { 00057 double latitude; 00058 double longitude; 00059 double velocity_north; 00060 double velocity_east; 00061 }; 00062 00063 namespace traits { 00064 template <> struct Update<GPSModel> { typedef GPSUpdate type; }; 00065 } 00066 00067 extern template class Measurement_<GPSModel>; 00068 00069 class GPS : public Measurement_<GPSModel> 00070 { 00071 public: 00072 EIGEN_MAKE_ALIGNED_OPERATOR_NEW 00073 00074 GPS(const std::string& name = "gps"); 00075 virtual ~GPS(); 00076 00077 virtual void onReset(); 00078 00079 virtual GPSModel::MeasurementVector const& getVector(const GPSUpdate &update, const State&); 00080 virtual bool prepareUpdate(State &state, const GPSUpdate &update); 00081 00082 private: 00083 bool auto_reference_; 00084 GlobalReferencePtr reference_; 00085 GPSModel::MeasurementVector y_; 00086 }; 00087 00088 } // namespace hector_pose_estimation 00089 00090 #endif // HECTOR_POSE_ESTIMATION_GPS_H