gazebo_imu_plugin.h
5.12 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
/*
* Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
* Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
* Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
* Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland
* Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include <random>
#include <Eigen/Core>
#include "Imu.pb.h"
#include <gazebo/common/common.hh>
#include <gazebo/common/Plugin.hh>
#include <gazebo/gazebo.hh>
#include <gazebo/physics/physics.hh>
#include <ignition/math.hh>
#include "gazebo/transport/transport.hh"
#include "gazebo/msgs/msgs.hh"
#include "common.h"
namespace gazebo {
//typedef const boost::shared_ptr<const sensor_msgs::msgs::Imu> ImuPtr;
// Default values for use with ADIS16448 IMU
static constexpr double kDefaultAdisGyroscopeNoiseDensity =
2.0 * 35.0 / 3600.0 / 180.0 * M_PI;
static constexpr double kDefaultAdisGyroscopeRandomWalk =
2.0 * 4.0 / 3600.0 / 180.0 * M_PI;
static constexpr double kDefaultAdisGyroscopeBiasCorrelationTime =
1.0e+3;
static constexpr double kDefaultAdisGyroscopeTurnOnBiasSigma =
0.5 / 180.0 * M_PI;
static constexpr double kDefaultAdisAccelerometerNoiseDensity =
2.0 * 2.0e-3;
static constexpr double kDefaultAdisAccelerometerRandomWalk =
2.0 * 3.0e-3;
static constexpr double kDefaultAdisAccelerometerBiasCorrelationTime =
300.0;
static constexpr double kDefaultAdisAccelerometerTurnOnBiasSigma =
20.0e-3 * 9.8;
// Earth's gravity in Zurich (lat=+47.3667degN, lon=+8.5500degE, h=+500m, WGS84)
static constexpr double kDefaultGravityMagnitude = 9.8068;
static const std::string kDefaultImuTopic = "imu";
// A description of the parameters:
// https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model-and-Intrinsics
// TODO(burrimi): Should I have a minimalistic description of the params here?
struct ImuParameters {
/// Gyroscope noise density (two-sided spectrum) [rad/s/sqrt(Hz)]
double gyroscope_noise_density;
/// Gyroscope bias random walk [rad/s/s/sqrt(Hz)]
double gyroscope_random_walk;
/// Gyroscope bias correlation time constant [s]
double gyroscope_bias_correlation_time;
/// Gyroscope turn on bias standard deviation [rad/s]
double gyroscope_turn_on_bias_sigma;
/// Accelerometer noise density (two-sided spectrum) [m/s^2/sqrt(Hz)]
double accelerometer_noise_density;
/// Accelerometer bias random walk. [m/s^2/s/sqrt(Hz)]
double accelerometer_random_walk;
/// Accelerometer bias correlation time constant [s]
double accelerometer_bias_correlation_time;
/// Accelerometer turn on bias standard deviation [m/s^2]
double accelerometer_turn_on_bias_sigma;
/// Norm of the gravitational acceleration [m/s^2]
double gravity_magnitude;
ImuParameters()
: gyroscope_noise_density(kDefaultAdisGyroscopeNoiseDensity),
gyroscope_random_walk(kDefaultAdisGyroscopeRandomWalk),
gyroscope_bias_correlation_time(
kDefaultAdisGyroscopeBiasCorrelationTime),
gyroscope_turn_on_bias_sigma(kDefaultAdisGyroscopeTurnOnBiasSigma),
accelerometer_noise_density(kDefaultAdisAccelerometerNoiseDensity),
accelerometer_random_walk(kDefaultAdisAccelerometerRandomWalk),
accelerometer_bias_correlation_time(
kDefaultAdisAccelerometerBiasCorrelationTime),
accelerometer_turn_on_bias_sigma(
kDefaultAdisAccelerometerTurnOnBiasSigma),
gravity_magnitude(kDefaultGravityMagnitude) {}
};
class GazeboImuPlugin : public ModelPlugin {
public:
GazeboImuPlugin();
~GazeboImuPlugin();
void InitializeParams();
void Publish();
protected:
void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
void addNoise(
Eigen::Vector3d* linear_acceleration,
Eigen::Vector3d* angular_velocity,
const double dt);
void OnUpdate(const common::UpdateInfo&);
private:
std::string namespace_;
std::string imu_topic_;
transport::NodePtr node_handle_;
transport::PublisherPtr imu_pub_;
std::string frame_id_;
std::string link_name_;
std::default_random_engine random_generator_;
std::normal_distribution<double> standard_normal_distribution_;
// Pointer to the world
physics::WorldPtr world_;
// Pointer to the model
physics::ModelPtr model_;
// Pointer to the link
physics::LinkPtr link_;
// Pointer to the update event connection
event::ConnectionPtr updateConnection_;
common::Time last_time_;
sensor_msgs::msgs::Imu imu_message_;
ignition::math::Vector3d gravity_W_;
ignition::math::Vector3d velocity_prev_W_;
Eigen::Vector3d gyroscope_bias_;
Eigen::Vector3d accelerometer_bias_;
ImuParameters imu_parameters_;
uint64_t seq_ = 0;
};
}