gazebo_ros_imu_sensor.h
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 
17 #ifndef GAZEBO_ROS_IMU_SENSOR_H
18 #define GAZEBO_ROS_IMU_SENSOR_H
19 
20 #include <gazebo/common/Plugin.hh>
21 #include <gazebo/common/UpdateInfo.hh>
22 #include <ignition/math/Vector3.hh>
23 #include <ignition/math/Pose3.hh>
24 #include <ros/ros.h>
25 #include <sensor_msgs/Imu.h>
26 #include <string>
27 
28 namespace gazebo
29 {
30  namespace sensors
31  {
32  class ImuSensor;
33  }
42  class GazeboRosImuSensor : public SensorPlugin
43  {
44  public:
48  virtual ~GazeboRosImuSensor();
52  virtual void Load(sensors::SensorPtr sensor_, sdf::ElementPtr sdf_);
53 
54  protected:
56  virtual void UpdateChild(const gazebo::common::UpdateInfo &/*_info*/);
57 
58  private:
60  bool LoadParameters();
64  double GuassianKernel(double mu, double sigma);
65 
71  sensor_msgs::Imu imu_msg;
72 
74  common::Time last_time;
76  gazebo::event::ConnectionPtr connection;
78  sensors::ImuSensor* sensor;
80  sdf::ElementPtr sdf;
82  ignition::math::Quaterniond orientation;
84  ignition::math::Vector3d accelerometer_data;
86  ignition::math::Vector3d gyroscope_data;
87 
89  unsigned int seed;
90 
91  //loaded parameters
93  std::string robot_namespace;
95  std::string topic_name;
97  std::string body_name;
99  double update_rate;
103  ignition::math::Pose3d offset;
104  };
105 }
106 
107 #endif //GAZEBO_ROS_IMU_SENSOR_H
double update_rate
Sensor update rate.
sdf::ElementPtr sdf
Pointer to the sdf config file.
std::string robot_namespace
The data is published on the topic named: /robot_namespace/topic_name.
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.
sensors::ImuSensor * sensor
Pointer to the sensor.
unsigned int seed
Seed for the Gaussian noise generator.
ignition::math::Quaterniond orientation
Orientation data from the sensor.
common::Time last_time
last time on which the data was published.
sensor_msgs::Imu imu_msg
Ros IMU message.
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.
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 Tue Mar 26 2019 02:31:27