Gazebo Ros imu sensor plugin. More...
#include <gazebo_ros_imu_sensor.h>
Public Member Functions | |
GazeboRosImuSensor () | |
Constructor. More... | |
virtual void | Load (sensors::SensorPtr sensor_, sdf::ElementPtr sdf_) |
Load the sensor. More... | |
virtual | ~GazeboRosImuSensor () |
Destructor. More... | |
Protected Member Functions | |
virtual void | UpdateChild (const gazebo::common::UpdateInfo &) |
Update the sensor. More... | |
Private Member Functions | |
double | GuassianKernel (double mu, double sigma) |
Gaussian noise generator. More... | |
bool | LoadParameters () |
Load the parameters from the sdf file. More... | |
Private Attributes | |
ignition::math::Vector3d | accelerometer_data |
Linear acceleration data from the sensor. More... | |
std::string | body_name |
Name of the link of the IMU. More... | |
gazebo::event::ConnectionPtr | connection |
Pointer to the update event connection. More... | |
double | gaussian_noise |
Gaussian noise. More... | |
ignition::math::Vector3d | gyroscope_data |
Angular velocity data from the sensor. More... | |
ros::Publisher | imu_data_publisher |
Ros Publisher for imu data. More... | |
sensor_msgs::Imu | imu_msg |
Ros IMU message. More... | |
common::Time | last_time |
last time on which the data was published. More... | |
ros::NodeHandle * | node |
Ros NodeHandle pointer. More... | |
ignition::math::Pose3d | offset |
Offset parameter, position part is unused. More... | |
ignition::math::Quaterniond | orientation |
Orientation data from the sensor. More... | |
std::string | robot_namespace |
The data is published on the topic named: /robot_namespace/topic_name. More... | |
sdf::ElementPtr | sdf |
Pointer to the sdf config file. More... | |
unsigned int | seed |
Seed for the Gaussian noise generator. More... | |
sensors::ImuSensor * | sensor |
Pointer to the sensor. More... | |
std::string | topic_name |
The data is published on the topic named: /robot_namespace/topic_name. More... | |
double | update_rate |
Sensor update rate. More... | |
Gazebo Ros imu sensor plugin.
GazeboRosImuSensor is a plugin to simulate an Inertial Motion Unit sensor, the main differences from GazeboRosIMU are:
Definition at line 42 of file gazebo_ros_imu_sensor.h.
gazebo::GazeboRosImuSensor::GazeboRosImuSensor | ( | ) |
Constructor.
Definition at line 24 of file gazebo_ros_imu_sensor.cpp.
|
virtual |
Destructor.
Definition at line 228 of file gazebo_ros_imu_sensor.cpp.
|
private |
Gaussian noise generator.
mu | offset value. |
sigma | scaling value. |
Definition at line 120 of file gazebo_ros_imu_sensor.cpp.
|
virtual |
Load the sensor.
sensor_ | pointer to the sensor. |
sdf_ | pointer to the sdf config file. |
Definition at line 33 of file gazebo_ros_imu_sensor.cpp.
|
private |
Load the parameters from the sdf file.
Definition at line 134 of file gazebo_ros_imu_sensor.cpp.
|
protectedvirtual |
Update the sensor.
Definition at line 67 of file gazebo_ros_imu_sensor.cpp.
|
private |
Linear acceleration data from the sensor.
Definition at line 84 of file gazebo_ros_imu_sensor.h.
|
private |
Name of the link of the IMU.
Definition at line 97 of file gazebo_ros_imu_sensor.h.
|
private |
Pointer to the update event connection.
Definition at line 76 of file gazebo_ros_imu_sensor.h.
|
private |
Gaussian noise.
Definition at line 101 of file gazebo_ros_imu_sensor.h.
|
private |
Angular velocity data from the sensor.
Definition at line 86 of file gazebo_ros_imu_sensor.h.
|
private |
Ros Publisher for imu data.
Definition at line 69 of file gazebo_ros_imu_sensor.h.
|
private |
Ros IMU message.
Definition at line 71 of file gazebo_ros_imu_sensor.h.
|
private |
last time on which the data was published.
Definition at line 74 of file gazebo_ros_imu_sensor.h.
|
private |
Ros NodeHandle pointer.
Definition at line 67 of file gazebo_ros_imu_sensor.h.
|
private |
Offset parameter, position part is unused.
Definition at line 103 of file gazebo_ros_imu_sensor.h.
|
private |
Orientation data from the sensor.
Definition at line 82 of file gazebo_ros_imu_sensor.h.
|
private |
The data is published on the topic named: /robot_namespace/topic_name.
Definition at line 93 of file gazebo_ros_imu_sensor.h.
|
private |
Pointer to the sdf config file.
Definition at line 80 of file gazebo_ros_imu_sensor.h.
|
private |
Seed for the Gaussian noise generator.
Definition at line 89 of file gazebo_ros_imu_sensor.h.
|
private |
Pointer to the sensor.
Definition at line 78 of file gazebo_ros_imu_sensor.h.
|
private |
The data is published on the topic named: /robot_namespace/topic_name.
Definition at line 95 of file gazebo_ros_imu_sensor.h.
|
private |
Sensor update rate.
Definition at line 99 of file gazebo_ros_imu_sensor.h.