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 #ifdef ENABLE_PROFILER
22 #include <ignition/common/Profiler.hh>
23 #endif
24 #include <ignition/math/Rand.hh>
25 
26 GZ_REGISTER_SENSOR_PLUGIN(gazebo::GazeboRosImuSensor)
27 
29 {
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);
33  sensor=NULL;
34 }
35 
36 void gazebo::GazeboRosImuSensor::Load(gazebo::sensors::SensorPtr sensor_, sdf::ElementPtr sdf_)
37 {
38  sdf=sdf_;
39  sensor=dynamic_cast<gazebo::sensors::ImuSensor*>(sensor_.get());
40 
41  if(sensor==NULL)
42  {
43  ROS_FATAL("Error: Sensor pointer is NULL!");
44  return;
45  }
46 
47  bool initial_orientation_as_reference = false;
48  if (!sdf->HasElement("initialOrientationAsReference"))
49  {
50  ROS_INFO("<initialOrientationAsReference> is unset, using default value of false "
51  "to comply with REP 145 (world as orientation reference)");
52  }
53  else
54  {
55  initial_orientation_as_reference = sdf->Get<bool>("initialOrientationAsReference");
56  }
57 
58  if (initial_orientation_as_reference)
59  {
60  ROS_WARN("<initialOrientationAsReference> set to true, this behavior is deprecated "
61  "as it does not comply with REP 145.");
62  }
63  else
64  {
65  // This complies with REP 145
66  sensor->SetWorldToReferenceOrientation(ignition::math::Quaterniond::Identity);
67  }
68 
69  sensor->SetActive(true);
70 
71  if(!LoadParameters())
72  {
73  ROS_FATAL("Error Loading Parameters!");
74  return;
75  }
76 
77  if (!ros::isInitialized()) //check if ros is initialized properly
78  {
79  ROS_FATAL("ROS has not been initialized!");
80  return;
81  }
82 
84 
85  imu_data_publisher = node->advertise<sensor_msgs::Imu>(topic_name,1);
86 
87  connection = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboRosImuSensor::UpdateChild, this, boost::placeholders::_1));
88 
89  last_time = sensor->LastUpdateTime();
90 }
91 
92 void gazebo::GazeboRosImuSensor::UpdateChild(const gazebo::common::UpdateInfo &/*_info*/)
93 {
94 #ifdef ENABLE_PROFILER
95  IGN_PROFILE("GazeboRosImuSensor::UpdateChild");
96 #endif
97  common::Time current_time = sensor->LastUpdateTime();
98 
99  if(update_rate>0 && (current_time-last_time).Double() < 1.0/update_rate) //update rate check
100  return;
101 
102  if(imu_data_publisher.getNumSubscribers() > 0)
103  {
104 #ifdef ENABLE_PROFILER
105  IGN_PROFILE_BEGIN("fill ROS message");
106 #endif
107  orientation = offset.Rot()*sensor->Orientation(); //applying offsets to the orientation measurement
108  accelerometer_data = sensor->LinearAcceleration();
109  gyroscope_data = sensor->AngularVelocity();
110 
111  //Guassian noise is applied to all measurements
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);
116 
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);
120 
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);
124 
125  //covariance is related to the 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;
136 
137  //preparing message header
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
142  IGN_PROFILE_END();
143  //publishing data
144  IGN_PROFILE_BEGIN("publish");
145 #endif
146  imu_data_publisher.publish(imu_msg);
147 #ifdef ENABLE_PROFILER
148  IGN_PROFILE_END();
149 #endif
150  ros::spinOnce();
151  }
152 
153  last_time = current_time;
154 }
155 
156 double gazebo::GazeboRosImuSensor::GuassianKernel(double mu, double sigma)
157 {
158  // generation of two normalized uniform random variables
159  double U1 = ignition::math::Rand::DblUniform();
160  double U2 = ignition::math::Rand::DblUniform();
161 
162  // using Box-Muller transform to obtain a varaible with a standard normal distribution
163  double Z0 = sqrt(-2.0 * ::log(U1)) * cos(2.0*M_PI * U2);
164 
165  // scaling
166  Z0 = sigma * Z0 + mu;
167  return Z0;
168 }
169 
171 {
172  //loading parameters from the sdf file
173 
174  //NAMESPACE
175  if (sdf->HasElement("robotNamespace"))
176  {
177  robot_namespace = sdf->Get<std::string>("robotNamespace") +"/";
178  ROS_INFO_STREAM("<robotNamespace> set to: "<<robot_namespace);
179  }
180  else
181  {
182  std::string scoped_name = sensor->ParentName();
183  std::size_t it = scoped_name.find("::");
184 
185  robot_namespace = "/" +scoped_name.substr(0,it)+"/";
186  ROS_WARN_STREAM("missing <robotNamespace>, set to default: " << robot_namespace);
187  }
188 
189  //TOPIC
190  if (sdf->HasElement("topicName"))
191  {
192  topic_name = sdf->Get<std::string>("topicName");
193  ROS_INFO_STREAM("<topicName> set to: "<<topic_name);
194  }
195  else
196  {
197  topic_name = "imu_data";
198  ROS_WARN_STREAM("missing <topicName>, set to /namespace/default: " << topic_name);
199  }
200 
201  //BODY NAME
202  if (sdf->HasElement("frameName"))
203  {
204  body_name = sdf->Get<std::string>("frameName");
205  ROS_INFO_STREAM("<frameName> set to: "<<body_name);
206  }
207  else
208  {
209  ROS_FATAL("missing <frameName>, cannot proceed");
210  return false;
211  }
212 
213  //UPDATE RATE
214  if (sdf->HasElement("updateRateHZ"))
215  {
216  update_rate = sdf->Get<double>("updateRateHZ");
217  ROS_INFO_STREAM("<updateRateHZ> set to: " << update_rate);
218  }
219  else
220  {
221  update_rate = 1.0;
222  ROS_WARN_STREAM("missing <updateRateHZ>, set to default: " << update_rate);
223  }
224 
225  //NOISE
226  if (sdf->HasElement("gaussianNoise"))
227  {
228  gaussian_noise = sdf->Get<double>("gaussianNoise");
229  ROS_INFO_STREAM("<gaussianNoise> set to: " << gaussian_noise);
230  }
231  else
232  {
233  gaussian_noise = 0.0;
234  ROS_WARN_STREAM("missing <gaussianNoise>, set to default: " << gaussian_noise);
235  }
236 
237  //POSITION OFFSET, UNUSED
238  if (sdf->HasElement("xyzOffset"))
239  {
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]);
242  }
243  else
244  {
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]);
247  }
248 
249  //ORIENTATION OFFSET
250  if (sdf->HasElement("rpyOffset"))
251  {
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());
254  }
255  else
256  {
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());
259  }
260 
261  return true;
262 }
263 
265 {
266  if (connection.get())
267  {
268  connection.reset();
269  connection = gazebo::event::ConnectionPtr();
270  }
271 
272  node->shutdown();
273 }
gazebo::GazeboRosImuSensor::LoadParameters
bool LoadParameters()
Load the parameters from the sdf file.
Definition: gazebo_ros_imu_sensor.cpp:170
gazebo::GazeboRosImuSensor::last_time
common::Time last_time
last time on which the data was published.
Definition: gazebo_ros_imu_sensor.h:74
gazebo::GazeboRosImuSensor
Gazebo Ros imu sensor plugin.
Definition: gazebo_ros_imu_sensor.h:42
gazebo
gazebo::GazeboRosImuSensor::Load
virtual void Load(sensors::SensorPtr sensor_, sdf::ElementPtr sdf_)
Load the sensor.
Definition: gazebo_ros_imu_sensor.cpp:36
gazebo::GazeboRosImuSensor::~GazeboRosImuSensor
virtual ~GazeboRosImuSensor()
Destructor.
Definition: gazebo_ros_imu_sensor.cpp:264
ros::spinOnce
ROSCPP_DECL void spinOnce()
gazebo_ros_imu_sensor.h
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
gazebo::GazeboRosImuSensor::connection
gazebo::event::ConnectionPtr connection
Pointer to the update event connection.
Definition: gazebo_ros_imu_sensor.h:76
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
gazebo::GazeboRosImuSensor::topic_name
std::string topic_name
The data is published on the topic named: /robot_namespace/topic_name.
Definition: gazebo_ros_imu_sensor.h:92
gazebo::GazeboRosImuSensor::sdf
sdf::ElementPtr sdf
Pointer to the sdf config file.
Definition: gazebo_ros_imu_sensor.h:80
ros::isInitialized
ROSCPP_DECL bool isInitialized()
ROS_WARN
#define ROS_WARN(...)
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
ROS_FATAL
#define ROS_FATAL(...)
gazebo::GazeboRosImuSensor::imu_data_publisher
ros::Publisher imu_data_publisher
Ros Publisher for imu data.
Definition: gazebo_ros_imu_sensor.h:69
gazebo::GazeboRosImuSensor::sensor
sensors::ImuSensor * sensor
Pointer to the sensor.
Definition: gazebo_ros_imu_sensor.h:78
gazebo::GazeboRosImuSensor::robot_namespace
std::string robot_namespace
The data is published on the topic named: /robot_namespace/topic_name.
Definition: gazebo_ros_imu_sensor.h:90
gazebo::GazeboRosImuSensor::node
ros::NodeHandle * node
Ros NodeHandle pointer.
Definition: gazebo_ros_imu_sensor.h:67
ROS_INFO
#define ROS_INFO(...)
gazebo::GazeboRosImuSensor::GuassianKernel
double GuassianKernel(double mu, double sigma)
Gaussian noise generator.
Definition: gazebo_ros_imu_sensor.cpp:156
gazebo::GazeboRosImuSensor::UpdateChild
virtual void UpdateChild(const gazebo::common::UpdateInfo &)
Update the sensor.
Definition: gazebo_ros_imu_sensor.cpp:92
ros::NodeHandle


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55