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 #ifndef HECTOR_POSE_ESTIMATION_IMvector_INPUT_H 00030 #define HECTOR_POSE_ESTIMATION_IMvector_INPUT_H 00031 00032 #include <hector_pose_estimation/input.h> 00033 #include <hector_pose_estimation/matrix.h> 00034 00035 #include <sensor_msgs/Imu.h> 00036 00037 namespace hector_pose_estimation { 00038 00039 class ImuInput : public Input_<6> 00040 { 00041 public: 00042 enum InputIndex { 00043 ACCEL_X = 0, 00044 ACCEL_Y, 00045 ACCEL_Z, 00046 GYRO_X, 00047 GYRO_Y, 00048 GYRO_Z 00049 }; 00050 typedef typename Vector::ConstFixedSegmentReturnType<3>::Type AccelerationType; 00051 typedef typename Vector::ConstFixedSegmentReturnType<3>::Type RateType; 00052 00053 ImuInput() {} 00054 ImuInput(const sensor_msgs::Imu& imu) { *this = imu; } 00055 virtual ~ImuInput() {} 00056 00057 virtual const std::string& getName() const { static std::string name("imu"); return name; } 00058 00059 ImuInput &operator=(const sensor_msgs::Imu& imu) { 00060 u_(ACCEL_X) = imu.linear_acceleration.x; 00061 u_(ACCEL_Y) = imu.linear_acceleration.y; 00062 u_(ACCEL_Z) = imu.linear_acceleration.z; 00063 u_(GYRO_X) = imu.angular_velocity.x; 00064 u_(GYRO_Y) = imu.angular_velocity.y; 00065 u_(GYRO_Z) = imu.angular_velocity.z; 00066 00067 // TODO: set variance if message contains non-zero covariance matrix 00068 return *this; 00069 } 00070 00071 AccelerationType getAcceleration() const { return u_.segment<3>(ACCEL_X); } 00072 RateType getRate() const { return u_.segment<3>(GYRO_X); } 00073 }; 00074 00075 } // namespace hector_pose_estimation 00076 00077 #endif // HECTOR_POSE_ESTIMATION_IMvector_INPUT_H