19 #include <gazebo/sensors/ImuSensor.hh>
20 #include <gazebo/physics/World.hh>
21 #ifdef ENABLE_PROFILER
22 #include <ignition/common/Profiler.hh>
24 #include <ignition/math/Rand.hh>
30 accelerometer_data = ignition::math::Vector3d(0, 0, 0);
31 gyroscope_data = ignition::math::Vector3d(0, 0, 0);
32 orientation = ignition::math::Quaterniond(1,0,0,0);
39 sensor=
dynamic_cast<gazebo::sensors::ImuSensor*
>(sensor_.get());
43 ROS_FATAL(
"Error: Sensor pointer is NULL!");
47 bool initial_orientation_as_reference =
false;
48 if (!
sdf->HasElement(
"initialOrientationAsReference"))
50 ROS_INFO(
"<initialOrientationAsReference> is unset, using default value of false "
51 "to comply with REP 145 (world as orientation reference)");
55 initial_orientation_as_reference =
sdf->Get<
bool>(
"initialOrientationAsReference");
58 if (initial_orientation_as_reference)
60 ROS_WARN(
"<initialOrientationAsReference> set to true, this behavior is deprecated "
61 "as it does not comply with REP 145.");
66 sensor->SetWorldToReferenceOrientation(ignition::math::Quaterniond::Identity);
79 ROS_FATAL(
"ROS has not been initialized!");
94 #ifdef ENABLE_PROFILER
95 IGN_PROFILE(
"GazeboRosImuSensor::UpdateChild");
97 common::Time current_time = sensor->LastUpdateTime();
99 if(update_rate>0 && (current_time-last_time).Double() < 1.0/update_rate)
102 if(imu_data_publisher.getNumSubscribers() > 0)
104 #ifdef ENABLE_PROFILER
105 IGN_PROFILE_BEGIN(
"fill ROS message");
107 orientation = offset.Rot()*sensor->Orientation();
108 accelerometer_data = sensor->LinearAcceleration();
109 gyroscope_data = sensor->AngularVelocity();
112 imu_msg.orientation.x = orientation.X() + GuassianKernel(0,gaussian_noise);
113 imu_msg.orientation.y = orientation.Y() + GuassianKernel(0,gaussian_noise);
114 imu_msg.orientation.z = orientation.Z() + GuassianKernel(0,gaussian_noise);
115 imu_msg.orientation.w = orientation.W() + GuassianKernel(0,gaussian_noise);
117 imu_msg.linear_acceleration.x = accelerometer_data.X() + GuassianKernel(0,gaussian_noise);
118 imu_msg.linear_acceleration.y = accelerometer_data.Y() + GuassianKernel(0,gaussian_noise);
119 imu_msg.linear_acceleration.z = accelerometer_data.Z() + GuassianKernel(0,gaussian_noise);
121 imu_msg.angular_velocity.x = gyroscope_data.X() + GuassianKernel(0,gaussian_noise);
122 imu_msg.angular_velocity.y = gyroscope_data.Y() + GuassianKernel(0,gaussian_noise);
123 imu_msg.angular_velocity.z = gyroscope_data.Z() + GuassianKernel(0,gaussian_noise);
126 double gn2 = gaussian_noise*gaussian_noise;
127 imu_msg.orientation_covariance[0] = gn2;
128 imu_msg.orientation_covariance[4] = gn2;
129 imu_msg.orientation_covariance[8] = gn2;
130 imu_msg.angular_velocity_covariance[0] = gn2;
131 imu_msg.angular_velocity_covariance[4] = gn2;
132 imu_msg.angular_velocity_covariance[8] = gn2;
133 imu_msg.linear_acceleration_covariance[0] = gn2;
134 imu_msg.linear_acceleration_covariance[4] = gn2;
135 imu_msg.linear_acceleration_covariance[8] = gn2;
138 imu_msg.header.frame_id = body_name;
139 imu_msg.header.stamp.sec = current_time.sec;
140 imu_msg.header.stamp.nsec = current_time.nsec;
141 #ifdef ENABLE_PROFILER
144 IGN_PROFILE_BEGIN(
"publish");
146 imu_data_publisher.publish(imu_msg);
147 #ifdef ENABLE_PROFILER
153 last_time = current_time;
159 double U1 = ignition::math::Rand::DblUniform();
160 double U2 = ignition::math::Rand::DblUniform();
163 double Z0 = sqrt(-2.0 * ::log(U1)) * cos(2.0*M_PI * U2);
166 Z0 = sigma * Z0 + mu;
175 if (sdf->HasElement(
"robotNamespace"))
177 robot_namespace = sdf->Get<std::string>(
"robotNamespace") +
"/";
182 std::string scoped_name = sensor->ParentName();
183 std::size_t it = scoped_name.find(
"::");
185 robot_namespace =
"/" +scoped_name.substr(0,it)+
"/";
186 ROS_WARN_STREAM(
"missing <robotNamespace>, set to default: " << robot_namespace);
190 if (sdf->HasElement(
"topicName"))
192 topic_name = sdf->Get<std::string>(
"topicName");
197 topic_name =
"imu_data";
198 ROS_WARN_STREAM(
"missing <topicName>, set to /namespace/default: " << topic_name);
202 if (sdf->HasElement(
"frameName"))
204 body_name = sdf->Get<std::string>(
"frameName");
209 ROS_FATAL(
"missing <frameName>, cannot proceed");
214 if (sdf->HasElement(
"updateRateHZ"))
216 update_rate = sdf->Get<
double>(
"updateRateHZ");
222 ROS_WARN_STREAM(
"missing <updateRateHZ>, set to default: " << update_rate);
226 if (sdf->HasElement(
"gaussianNoise"))
228 gaussian_noise = sdf->Get<
double>(
"gaussianNoise");
233 gaussian_noise = 0.0;
234 ROS_WARN_STREAM(
"missing <gaussianNoise>, set to default: " << gaussian_noise);
238 if (sdf->HasElement(
"xyzOffset"))
240 offset.Pos() = sdf->Get<ignition::math::Vector3d>(
"xyzOffset");
241 ROS_INFO_STREAM(
"<xyzOffset> set to: " << offset.Pos()[0] <<
' ' << offset.Pos()[1] <<
' ' << offset.Pos()[2]);
245 offset.Pos() = ignition::math::Vector3d(0, 0, 0);
246 ROS_WARN_STREAM(
"missing <xyzOffset>, set to default: " << offset.Pos()[0] <<
' ' << offset.Pos()[1] <<
' ' << offset.Pos()[2]);
250 if (sdf->HasElement(
"rpyOffset"))
252 offset.Rot() = ignition::math::Quaterniond(sdf->Get<ignition::math::Vector3d>(
"rpyOffset"));
253 ROS_INFO_STREAM(
"<rpyOffset> set to: " << offset.Rot().Roll() <<
' ' << offset.Rot().Pitch() <<
' ' << offset.Rot().Yaw());
257 offset.Rot() = ignition::math::Quaterniond::Identity;
258 ROS_WARN_STREAM(
"missing <rpyOffset>, set to default: " << offset.Rot().Roll() <<
' ' << offset.Rot().Pitch() <<
' ' << offset.Rot().Yaw());
266 if (connection.get())
269 connection = gazebo::event::ConnectionPtr();