gazebo_imu_plugin.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
3  * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
4  * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
5  * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland
6  * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
7  * Copyright 2016 Geoffrey Hunter <gbmhunter@gmail.com>
8  *
9  * Licensed under the Apache License, Version 2.0 (the "License");
10  * you may not use this file except in compliance with the License.
11  * You may obtain a copy of the License at
12  *
13  * http://www.apache.org/licenses/LICENSE-2.0
14 
15  * Unless required by applicable law or agreed to in writing, software
16  * distributed under the License is distributed on an "AS IS" BASIS,
17  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
18  * See the License for the specific language governing permissions and
19  * limitations under the License.
20  */
21 
22 #ifndef ROTORS_GAZEBO_PLUGINS_IMU_PLUGIN_H
23 #define ROTORS_GAZEBO_PLUGINS_IMU_PLUGIN_H
24 
25 #include <random>
26 
27 #include <Eigen/Core>
28 #include <gazebo/common/common.hh>
29 #include <gazebo/common/Plugin.hh>
30 #include <gazebo/gazebo.hh>
31 #include <gazebo/physics/physics.hh>
32 
33 #include "Imu.pb.h"
34 
36 
37 namespace gazebo {
38 
39 // Default values for use with ADIS16448 IMU
40 static constexpr double kDefaultAdisGyroscopeNoiseDensity =
41  2.0 * 35.0 / 3600.0 / 180.0 * M_PI;
42 static constexpr double kDefaultAdisGyroscopeRandomWalk =
43  2.0 * 4.0 / 3600.0 / 180.0 * M_PI;
45  1.0e+3;
46 static constexpr double kDefaultAdisGyroscopeTurnOnBiasSigma =
47  0.5 / 180.0 * M_PI;
48 static constexpr double kDefaultAdisAccelerometerNoiseDensity =
49  2.0 * 2.0e-3;
50 static constexpr double kDefaultAdisAccelerometerRandomWalk =
51  2.0 * 3.0e-3;
53  300.0;
55  20.0e-3 * 9.8;
56 // Earth's gravity in Zurich (lat=+47.3667degN, lon=+8.5500degE, h=+500m, WGS84)
57 static constexpr double kDefaultGravityMagnitude = 9.8068;
58 
59 // A description of the parameters:
60 // https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model-and-Intrinsics
61 // TODO(burrimi): Should I have a minimalistic description of the params here?
62 struct ImuParameters {
81 
83  : gyroscope_noise_density(kDefaultAdisGyroscopeNoiseDensity),
84  gyroscope_random_walk(kDefaultAdisGyroscopeRandomWalk),
85  gyroscope_bias_correlation_time(
86  kDefaultAdisGyroscopeBiasCorrelationTime),
87  gyroscope_turn_on_bias_sigma(kDefaultAdisGyroscopeTurnOnBiasSigma),
88  accelerometer_noise_density(kDefaultAdisAccelerometerNoiseDensity),
89  accelerometer_random_walk(kDefaultAdisAccelerometerRandomWalk),
90  accelerometer_bias_correlation_time(
91  kDefaultAdisAccelerometerBiasCorrelationTime),
92  accelerometer_turn_on_bias_sigma(
93  kDefaultAdisAccelerometerTurnOnBiasSigma),
94  gravity_magnitude(kDefaultGravityMagnitude) {}
95 };
96 
97 class GazeboImuPlugin : public ModelPlugin {
98  public:
99 
100  GazeboImuPlugin();
101  ~GazeboImuPlugin();
102 
103  void InitializeParams();
104  void Publish();
105 
106  protected:
107  void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
108 
111  void AddNoise(
112  Eigen::Vector3d* linear_acceleration,
113  Eigen::Vector3d* angular_velocity,
114  const double dt);
115 
118  void OnUpdate(const common::UpdateInfo&);
119 
120  private:
121 
125 
130  void CreatePubsAndSubs();
131 
132 
133  std::string namespace_;
134  std::string imu_topic_;
135 
137  transport::NodePtr node_handle_;
138 
139  transport::PublisherPtr imu_pub_;
140 
141  std::string frame_id_;
142  std::string link_name_;
143 
144  std::default_random_engine random_generator_;
145  std::normal_distribution<double> standard_normal_distribution_;
146 
148  physics::WorldPtr world_;
149 
151  physics::ModelPtr model_;
152 
154  physics::LinkPtr link_;
155 
157  event::ConnectionPtr updateConnection_;
158 
159  common::Time last_time_;
160 
163  // and then published onto a topic
164  gz_sensor_msgs::Imu imu_message_;
165 
166  ignition::math::Vector3d gravity_W_;
167  ignition::math::Vector3d velocity_prev_W_;
168 
169  Eigen::Vector3d gyroscope_bias_;
170  Eigen::Vector3d accelerometer_bias_;
171 
172  Eigen::Vector3d gyroscope_turn_on_bias_;
174 
176 };
177 
178 } // namespace gazebo
179 
180 #endif // ROTORS_GAZEBO_PLUGINS_IMU_PLUGIN_H
physics::LinkPtr link_
Pointer to the link.
Eigen::Vector3d gyroscope_bias_
bool pubs_and_subs_created_
Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from...
Eigen::Vector3d accelerometer_turn_on_bias_
static constexpr double kDefaultAdisGyroscopeTurnOnBiasSigma
static constexpr double kDefaultAdisGyroscopeBiasCorrelationTime
static constexpr double kDefaultGravityMagnitude
double gyroscope_random_walk
Gyroscope bias random walk [rad/s/s/sqrt(Hz)].
std::default_random_engine random_generator_
event::ConnectionPtr updateConnection_
Pointer to the update event connection.
static constexpr double kDefaultAdisAccelerometerRandomWalk
physics::ModelPtr model_
Pointer to the model.
physics::WorldPtr world_
Pointer to the world.
#define M_PI
gz_sensor_msgs::Imu imu_message_
IMU message.
ignition::math::Vector3d gravity_W_
static constexpr double kDefaultAdisGyroscopeNoiseDensity
static constexpr double kDefaultAdisAccelerometerNoiseDensity
static constexpr double kDefaultAdisAccelerometerTurnOnBiasSigma
double accelerometer_turn_on_bias_sigma
Accelerometer turn on bias standard deviation [m/s^2].
static constexpr double kDefaultAdisAccelerometerBiasCorrelationTime
double accelerometer_random_walk
Accelerometer bias random walk. [m/s^2/s/sqrt(Hz)].
double gyroscope_bias_correlation_time
Gyroscope bias correlation time constant [s].
Eigen::Vector3d gyroscope_turn_on_bias_
double gyroscope_turn_on_bias_sigma
Gyroscope turn on bias standard deviation [rad/s].
double accelerometer_noise_density
Accelerometer noise density (two-sided spectrum) [m/s^2/sqrt(Hz)].
ignition::math::Vector3d velocity_prev_W_
double gyroscope_noise_density
Gyroscope noise density (two-sided spectrum) [rad/s/sqrt(Hz)].
std::normal_distribution< double > standard_normal_distribution_
transport::NodePtr node_handle_
Handle for the Gazebo node.
static constexpr double kDefaultAdisGyroscopeRandomWalk
Eigen::Vector3d accelerometer_bias_
double gravity_magnitude
Norm of the gravitational acceleration [m/s^2].
transport::PublisherPtr imu_pub_
double accelerometer_bias_correlation_time
Accelerometer bias correlation time constant [s].


rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:39:03