imu_input.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef HECTOR_POSE_ESTIMATION_IMvector_INPUT_H
30 #define HECTOR_POSE_ESTIMATION_IMvector_INPUT_H
31 
34 
35 #include <sensor_msgs/Imu.h>
36 
37 namespace hector_pose_estimation {
38 
39 class ImuInput : public Input_<6>
40 {
41 public:
42  enum InputIndex {
43  ACCEL_X = 0,
49  };
50  typedef typename Vector::ConstFixedSegmentReturnType<3>::Type AccelerationType;
51  typedef typename Vector::ConstFixedSegmentReturnType<3>::Type RateType;
52 
53  ImuInput() {}
54  ImuInput(const sensor_msgs::Imu& imu) { *this = imu; }
55  virtual ~ImuInput() {}
56 
57  virtual const std::string& getName() const { static std::string name("imu"); return name; }
58 
59  ImuInput &operator=(const sensor_msgs::Imu& imu) {
60  u_(ACCEL_X) = imu.linear_acceleration.x;
61  u_(ACCEL_Y) = imu.linear_acceleration.y;
62  u_(ACCEL_Z) = imu.linear_acceleration.z;
63  u_(GYRO_X) = imu.angular_velocity.x;
64  u_(GYRO_Y) = imu.angular_velocity.y;
65  u_(GYRO_Z) = imu.angular_velocity.z;
66 
67  // TODO: set variance if message contains non-zero covariance matrix
68  return *this;
69  }
70 
71  AccelerationType getAcceleration() const { return u_.segment<3>(ACCEL_X); }
72  RateType getRate() const { return u_.segment<3>(GYRO_X); }
73 };
74 
75 } // namespace hector_pose_estimation
76 
77 #endif // HECTOR_POSE_ESTIMATION_IMvector_INPUT_H
virtual const std::string & getName() const
Definition: imu_input.h:57
RateType getRate() const
Definition: imu_input.h:72
Vector::ConstFixedSegmentReturnType< 3 >::Type AccelerationType
Definition: imu_input.h:50
ImuInput(const sensor_msgs::Imu &imu)
Definition: imu_input.h:54
AccelerationType getAcceleration() const
Definition: imu_input.h:71
ImuInput & operator=(const sensor_msgs::Imu &imu)
Definition: imu_input.h:59
Vector::ConstFixedSegmentReturnType< 3 >::Type RateType
Definition: imu_input.h:51


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Thu Feb 18 2021 03:29:30