NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
imu_measurement.h
Go to the documentation of this file.
1 /* Copyright (c) 2017, United States Government, as represented by the
2  * Administrator of the National Aeronautics and Space Administration.
3  *
4  * All rights reserved.
5  *
6  * The Astrobee platform is licensed under the Apache License, Version 2.0
7  * (the "License"); you may not use this file except in compliance with the
8  * License. You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14  * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15  * License for the specific language governing permissions and limitations
16  * under the License.
17  */
18 
19 #ifndef LOCALIZATION_MEASUREMENTS_IMU_MEASUREMENT_H_
20 #define LOCALIZATION_MEASUREMENTS_IMU_MEASUREMENT_H_
21 
24 
25 #include <Eigen/Core>
26 
27 #include <sensor_msgs/Imu.h>
28 
29 namespace localization_measurements {
30 struct ImuMeasurement : public Measurement {
31  explicit ImuMeasurement(const sensor_msgs::Imu& imu_msg) {
32  acceleration.x() = imu_msg.linear_acceleration.x;
33  acceleration.y() = imu_msg.linear_acceleration.y;
34  acceleration.z() = imu_msg.linear_acceleration.z;
35  angular_velocity.x() = imu_msg.angular_velocity.x;
36  angular_velocity.y() = imu_msg.angular_velocity.y;
37  angular_velocity.z() = imu_msg.angular_velocity.z;
38  // Ros headers are stored as seconds and nanoseconds
39  timestamp = imu_msg.header.stamp.sec + 1e-9 * imu_msg.header.stamp.nsec;
40  }
44 
45  ImuMeasurement() = default;
46 
49 };
50 } // namespace localization_measurements
51 
52 #endif // LOCALIZATION_MEASUREMENTS_IMU_MEASUREMENT_H_
localization_measurements::ImuMeasurement
Definition: imu_measurement.h:30
localization_measurements::ImuMeasurement::ImuMeasurement
ImuMeasurement(const sensor_msgs::Imu &imu_msg)
Definition: imu_measurement.h:31
localization_measurements::Measurement::timestamp
localization_common::Time timestamp
Definition: measurement.h:29
localization_measurements::ImuMeasurement::acceleration
Eigen::Vector3d acceleration
Definition: imu_measurement.h:47
measurement.h
point_cloud_common::Vector3d
Eigen::Vector3d Vector3d(const PointType &point)
Definition: utilities.h:328
time.h
localization_measurements::Measurement
Definition: measurement.h:25
localization_measurements
Definition: depth_correspondences.h:25
localization_measurements::ImuMeasurement::angular_velocity
Eigen::Vector3d angular_velocity
Definition: imu_measurement.h:48
localization_measurements::ImuMeasurement::ImuMeasurement
ImuMeasurement()=default
localization_measurements::ImuMeasurement::ImuMeasurement
ImuMeasurement(const Eigen::Vector3d &acceleration, const Eigen::Vector3d &angular_velocity, const localization_common::Time timestamp)
Definition: imu_measurement.h:41
localization_common::Time
double Time
Definition: time.h:23