00001 //================================================================================================= 00002 // Copyright (c) 2012, 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 #include <hector_pose_estimation/system_input.h> 00030 #include <hector_pose_estimation/matrix.h> 00031 #include <sensor_msgs/Imu.h> 00032 00033 #ifndef HECTOR_POSE_ESTIMATION_IMU_INPUT_H 00034 #define HECTOR_POSE_ESTIMATION_IMU_INPUT_H 00035 00036 namespace hector_pose_estimation { 00037 00038 class ImuInput : public SystemInput 00039 { 00040 public: 00041 enum InputIndex { 00042 ACCEL_X = 1, 00043 ACCEL_Y, 00044 ACCEL_Z, 00045 GYRO_X, 00046 GYRO_Y, 00047 GYRO_Z 00048 }; 00049 static const unsigned int InputDimension = GYRO_Z; 00050 typedef ColumnVector_<InputDimension> InputVector; 00051 00052 ImuInput() 00053 : u_(InputDimension) 00054 {} 00055 ImuInput(InputVector const& u) 00056 : u_(InputDimension) 00057 { 00058 setValue(u); 00059 } 00060 ImuInput(const sensor_msgs::Imu& imu) 00061 : u_(InputDimension) 00062 { 00063 setValue(imu); 00064 } 00065 virtual ~ImuInput() {} 00066 00067 virtual void setValue(InputVector const& u) { u_ = u; } 00068 virtual void setValue(const sensor_msgs::Imu& imu) { 00069 u_(ACCEL_X) = imu.linear_acceleration.x; 00070 u_(ACCEL_Y) = imu.linear_acceleration.y; 00071 u_(ACCEL_Z) = imu.linear_acceleration.z; 00072 u_(GYRO_X) = imu.angular_velocity.x; 00073 u_(GYRO_Y) = imu.angular_velocity.y; 00074 u_(GYRO_Z) = imu.angular_velocity.z; 00075 } 00076 00077 virtual InputVector const &getVector() const { return u_; } 00078 virtual ColumnVector_<3> getAccel() const { return u_.sub(ACCEL_X, ACCEL_Z); } 00079 virtual ColumnVector_<3> getRate() const { return u_.sub(GYRO_X, GYRO_Z); } 00080 00081 virtual InputVector &operator=(InputVector const& u) { setValue(u); return u_; } 00082 virtual InputVector &operator=(const sensor_msgs::Imu& imu) { setValue(imu); return u_; } 00083 00084 protected: 00085 InputVector u_; 00086 }; 00087 00088 } // namespace hector_pose_estimation 00089 00090 #endif // HECTOR_POSE_ESTIMATION_IMU_INPUT_H