gazebo_ros_imu_sensor.cpp
Go to the documentation of this file.
1 /* Copyright [2015] [Alessandro Settimi]
2  *
3  * email: ale.settimi@gmail.com
4  *
5  * Licensed under the Apache License, Version 2.0 (the "License");
6  * you may not use this file except in compliance with the License.
7  * You may obtain a copy of the License at
8  *
9  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.*/
16 
18 #include <iostream>
19 #include <gazebo/sensors/ImuSensor.hh>
20 #include <gazebo/physics/World.hh>
21 #include <ignition/math/Rand.hh>
22 
23 GZ_REGISTER_SENSOR_PLUGIN(gazebo::GazeboRosImuSensor)
24 
26 {
27  accelerometer_data = ignition::math::Vector3d(0, 0, 0);
28  gyroscope_data = ignition::math::Vector3d(0, 0, 0);
29  orientation = ignition::math::Quaterniond(1,0,0,0);
30  sensor=NULL;
31 }
32 
33 void gazebo::GazeboRosImuSensor::Load(gazebo::sensors::SensorPtr sensor_, sdf::ElementPtr sdf_)
34 {
35  sdf=sdf_;
36  sensor=dynamic_cast<gazebo::sensors::ImuSensor*>(sensor_.get());
37 
38  if(sensor==NULL)
39  {
40  ROS_FATAL("Error: Sensor pointer is NULL!");
41  return;
42  }
43 
44  if (sdf->HasElement("initialOrientationAsReference"))
45  {
46  bool initial_orientation_as_reference = sdf->Get<bool>("initialOrientationAsReference");
47  ROS_INFO_STREAM("<initialOrientationAsReference> set to: "<< initial_orientation_as_reference);
48  if (!initial_orientation_as_reference) {
49  // This complies with REP 145
50  sensor->SetWorldToReferenceOrientation(ignition::math::Quaterniond::Identity);
51  }
52  }
53 
54  sensor->SetActive(true);
55 
56  if(!LoadParameters())
57  {
58  ROS_FATAL("Error Loading Parameters!");
59  return;
60  }
61 
62  if (!ros::isInitialized()) //check if ros is initialized properly
63  {
64  ROS_FATAL("ROS has not been initialized!");
65  return;
66  }
67 
69 
70  imu_data_publisher = node->advertise<sensor_msgs::Imu>(topic_name,1);
71 
72  connection = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosImuSensor::UpdateChild, this, _1));
73 
74  last_time = sensor->LastUpdateTime();
75 }
76 
77 void gazebo::GazeboRosImuSensor::UpdateChild(const gazebo::common::UpdateInfo &/*_info*/)
78 {
79  common::Time current_time = sensor->LastUpdateTime();
80 
81  if(update_rate>0 && (current_time-last_time).Double() < 1.0/update_rate) //update rate check
82  return;
83 
85  {
86  orientation = offset.Rot()*sensor->Orientation(); //applying offsets to the orientation measurement
87  accelerometer_data = sensor->LinearAcceleration();
88  gyroscope_data = sensor->AngularVelocity();
89 
90  //Guassian noise is applied to all measurements
91  imu_msg.orientation.x = orientation.X() + GuassianKernel(0,gaussian_noise);
92  imu_msg.orientation.y = orientation.Y() + GuassianKernel(0,gaussian_noise);
93  imu_msg.orientation.z = orientation.Z() + GuassianKernel(0,gaussian_noise);
94  imu_msg.orientation.w = orientation.W() + GuassianKernel(0,gaussian_noise);
95 
96  imu_msg.linear_acceleration.x = accelerometer_data.X() + GuassianKernel(0,gaussian_noise);
97  imu_msg.linear_acceleration.y = accelerometer_data.Y() + GuassianKernel(0,gaussian_noise);
98  imu_msg.linear_acceleration.z = accelerometer_data.Z() + GuassianKernel(0,gaussian_noise);
99 
100  imu_msg.angular_velocity.x = gyroscope_data.X() + GuassianKernel(0,gaussian_noise);
101  imu_msg.angular_velocity.y = gyroscope_data.Y() + GuassianKernel(0,gaussian_noise);
102  imu_msg.angular_velocity.z = gyroscope_data.Z() + GuassianKernel(0,gaussian_noise);
103 
104  //covariance is related to the Gaussian noise
105  double gn2 = gaussian_noise*gaussian_noise;
106  imu_msg.orientation_covariance[0] = gn2;
107  imu_msg.orientation_covariance[4] = gn2;
108  imu_msg.orientation_covariance[8] = gn2;
109  imu_msg.angular_velocity_covariance[0] = gn2;
110  imu_msg.angular_velocity_covariance[4] = gn2;
111  imu_msg.angular_velocity_covariance[8] = gn2;
112  imu_msg.linear_acceleration_covariance[0] = gn2;
113  imu_msg.linear_acceleration_covariance[4] = gn2;
114  imu_msg.linear_acceleration_covariance[8] = gn2;
115 
116  //preparing message header
117  imu_msg.header.frame_id = body_name;
118  imu_msg.header.stamp.sec = current_time.sec;
119  imu_msg.header.stamp.nsec = current_time.nsec;
120 
121  //publishing data
123 
124  ros::spinOnce();
125  }
126 
127  last_time = current_time;
128 }
129 
130 double gazebo::GazeboRosImuSensor::GuassianKernel(double mu, double sigma)
131 {
132  // generation of two normalized uniform random variables
133  double U1 = ignition::math::Rand::DblUniform();
134  double U2 = ignition::math::Rand::DblUniform();
135 
136  // using Box-Muller transform to obtain a varaible with a standard normal distribution
137  double Z0 = sqrt(-2.0 * ::log(U1)) * cos(2.0*M_PI * U2);
138 
139  // scaling
140  Z0 = sigma * Z0 + mu;
141  return Z0;
142 }
143 
145 {
146  //loading parameters from the sdf file
147 
148  //NAMESPACE
149  if (sdf->HasElement("robotNamespace"))
150  {
151  robot_namespace = sdf->Get<std::string>("robotNamespace") +"/";
152  ROS_INFO_STREAM("<robotNamespace> set to: "<<robot_namespace);
153  }
154  else
155  {
156  std::string scoped_name = sensor->ParentName();
157  std::size_t it = scoped_name.find("::");
158 
159  robot_namespace = "/" +scoped_name.substr(0,it)+"/";
160  ROS_WARN_STREAM("missing <robotNamespace>, set to default: " << robot_namespace);
161  }
162 
163  //TOPIC
164  if (sdf->HasElement("topicName"))
165  {
166  topic_name = robot_namespace + sdf->Get<std::string>("topicName");
167  ROS_INFO_STREAM("<topicName> set to: "<<topic_name);
168  }
169  else
170  {
171  topic_name = robot_namespace + "/imu_data";
172  ROS_WARN_STREAM("missing <topicName>, set to /namespace/default: " << topic_name);
173  }
174 
175  //BODY NAME
176  if (sdf->HasElement("frameName"))
177  {
178  body_name = sdf->Get<std::string>("frameName");
179  ROS_INFO_STREAM("<frameName> set to: "<<body_name);
180  }
181  else
182  {
183  ROS_FATAL("missing <frameName>, cannot proceed");
184  return false;
185  }
186 
187  //UPDATE RATE
188  if (sdf->HasElement("updateRateHZ"))
189  {
190  update_rate = sdf->Get<double>("updateRateHZ");
191  ROS_INFO_STREAM("<updateRateHZ> set to: " << update_rate);
192  }
193  else
194  {
195  update_rate = 1.0;
196  ROS_WARN_STREAM("missing <updateRateHZ>, set to default: " << update_rate);
197  }
198 
199  //NOISE
200  if (sdf->HasElement("gaussianNoise"))
201  {
202  gaussian_noise = sdf->Get<double>("gaussianNoise");
203  ROS_INFO_STREAM("<gaussianNoise> set to: " << gaussian_noise);
204  }
205  else
206  {
207  gaussian_noise = 0.0;
208  ROS_WARN_STREAM("missing <gaussianNoise>, set to default: " << gaussian_noise);
209  }
210 
211  //POSITION OFFSET, UNUSED
212  if (sdf->HasElement("xyzOffset"))
213  {
214  offset.Pos() = sdf->Get<ignition::math::Vector3d>("xyzOffset");
215  ROS_INFO_STREAM("<xyzOffset> set to: " << offset.Pos()[0] << ' ' << offset.Pos()[1] << ' ' << offset.Pos()[2]);
216  }
217  else
218  {
219  offset.Pos() = ignition::math::Vector3d(0, 0, 0);
220  ROS_WARN_STREAM("missing <xyzOffset>, set to default: " << offset.Pos()[0] << ' ' << offset.Pos()[1] << ' ' << offset.Pos()[2]);
221  }
222 
223  //ORIENTATION OFFSET
224  if (sdf->HasElement("rpyOffset"))
225  {
226  offset.Rot() = ignition::math::Quaterniond(sdf->Get<ignition::math::Vector3d>("rpyOffset"));
227  ROS_INFO_STREAM("<rpyOffset> set to: " << offset.Rot().Roll() << ' ' << offset.Rot().Pitch() << ' ' << offset.Rot().Yaw());
228  }
229  else
230  {
231  offset.Rot() = ignition::math::Quaterniond::Identity;
232  ROS_WARN_STREAM("missing <rpyOffset>, set to default: " << offset.Rot().Roll() << ' ' << offset.Rot().Pitch() << ' ' << offset.Rot().Yaw());
233  }
234 
235  return true;
236 }
237 
239 {
240  if (connection.get())
241  {
242  connection.reset();
243  connection = gazebo::event::ConnectionPtr();
244  }
245 
246  node->shutdown();
247 }
double update_rate
Sensor update rate.
sdf::ElementPtr sdf
Pointer to the sdf config file.
#define ROS_FATAL(...)
std::string robot_namespace
The data is published on the topic named: /robot_namespace/topic_name.
ROSCPP_DECL bool isInitialized()
double GuassianKernel(double mu, double sigma)
Gaussian noise generator.
ros::Publisher imu_data_publisher
Ros Publisher for imu data.
Gazebo Ros imu sensor plugin.
double gaussian_noise
Gaussian noise.
ignition::math::Vector3d accelerometer_data
Linear acceleration data from the sensor.
ignition::math::Vector3d gyroscope_data
Angular velocity data from the sensor.
ros::NodeHandle * node
Ros NodeHandle pointer.
void publish(const boost::shared_ptr< M > &message) const
sensors::ImuSensor * sensor
Pointer to the sensor.
virtual void Load(sensors::SensorPtr sensor_, sdf::ElementPtr sdf_)
Load the sensor.
ignition::math::Quaterniond orientation
Orientation data from the sensor.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual void UpdateChild(const gazebo::common::UpdateInfo &)
Update the sensor.
#define ROS_WARN_STREAM(args)
virtual ~GazeboRosImuSensor()
Destructor.
bool LoadParameters()
Load the parameters from the sdf file.
common::Time last_time
last time on which the data was published.
sensor_msgs::Imu imu_msg
Ros IMU message.
#define ROS_INFO_STREAM(args)
gazebo::event::ConnectionPtr connection
Pointer to the update event connection.
std::string topic_name
The data is published on the topic named: /robot_namespace/topic_name.
uint32_t getNumSubscribers() const
ROSCPP_DECL void spinOnce()
ignition::math::Pose3d offset
Offset parameter, position part is unused.
std::string body_name
Name of the link of the IMU.


gazebo_plugins
Author(s): John Hsu
autogenerated on Wed Aug 24 2022 02:47:52