17 #ifndef GAZEBO_ROS_IMU_SENSOR_H 18 #define GAZEBO_ROS_IMU_SENSOR_H 20 #include <gazebo/common/Plugin.hh> 21 #include <gazebo/common/UpdateInfo.hh> 22 #include <ignition/math/Vector3.hh> 23 #include <ignition/math/Pose3.hh> 25 #include <sensor_msgs/Imu.h> 52 virtual void Load(sensors::SensorPtr sensor_, sdf::ElementPtr sdf_);
56 virtual void UpdateChild(
const gazebo::common::UpdateInfo &);
60 bool LoadParameters();
64 double GuassianKernel(
double mu,
double sigma);
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.