Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::GazeboRosImuSensor Class Reference

Gazebo Ros imu sensor plugin. More...

#include <gazebo_ros_imu_sensor.h>

Inheritance diagram for gazebo::GazeboRosImuSensor:
Inheritance graph
[legend]

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::NodeHandlenode
 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...
 
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...
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ GazeboRosImuSensor()

gazebo::GazeboRosImuSensor::GazeboRosImuSensor ( )

Constructor.

Definition at line 28 of file gazebo_ros_imu_sensor.cpp.

◆ ~GazeboRosImuSensor()

gazebo::GazeboRosImuSensor::~GazeboRosImuSensor ( )
virtual

Destructor.

Definition at line 264 of file gazebo_ros_imu_sensor.cpp.

Member Function Documentation

◆ GuassianKernel()

double gazebo::GazeboRosImuSensor::GuassianKernel ( double  mu,
double  sigma 
)
private

Gaussian noise generator.

Parameters
muoffset value.
sigmascaling value.

Definition at line 156 of file gazebo_ros_imu_sensor.cpp.

◆ Load()

void gazebo::GazeboRosImuSensor::Load ( sensors::SensorPtr  sensor_,
sdf::ElementPtr  sdf_ 
)
virtual

Load the sensor.

Parameters
sensor_pointer to the sensor.
sdf_pointer to the sdf config file.

Definition at line 36 of file gazebo_ros_imu_sensor.cpp.

◆ LoadParameters()

bool gazebo::GazeboRosImuSensor::LoadParameters ( )
private

Load the parameters from the sdf file.

Definition at line 170 of file gazebo_ros_imu_sensor.cpp.

◆ UpdateChild()

void gazebo::GazeboRosImuSensor::UpdateChild ( const gazebo::common::UpdateInfo &  )
protectedvirtual

Update the sensor.

Definition at line 92 of file gazebo_ros_imu_sensor.cpp.

Member Data Documentation

◆ accelerometer_data

ignition::math::Vector3d gazebo::GazeboRosImuSensor::accelerometer_data
private

Linear acceleration data from the sensor.

Definition at line 84 of file gazebo_ros_imu_sensor.h.

◆ body_name

std::string gazebo::GazeboRosImuSensor::body_name
private

Name of the link of the IMU.

Definition at line 94 of file gazebo_ros_imu_sensor.h.

◆ connection

gazebo::event::ConnectionPtr gazebo::GazeboRosImuSensor::connection
private

Pointer to the update event connection.

Definition at line 76 of file gazebo_ros_imu_sensor.h.

◆ gaussian_noise

double gazebo::GazeboRosImuSensor::gaussian_noise
private

Gaussian noise.

Definition at line 98 of file gazebo_ros_imu_sensor.h.

◆ gyroscope_data

ignition::math::Vector3d gazebo::GazeboRosImuSensor::gyroscope_data
private

Angular velocity data from the sensor.

Definition at line 86 of file gazebo_ros_imu_sensor.h.

◆ imu_data_publisher

ros::Publisher gazebo::GazeboRosImuSensor::imu_data_publisher
private

Ros Publisher for imu data.

Definition at line 69 of file gazebo_ros_imu_sensor.h.

◆ imu_msg

sensor_msgs::Imu gazebo::GazeboRosImuSensor::imu_msg
private

Ros IMU message.

Definition at line 71 of file gazebo_ros_imu_sensor.h.

◆ last_time

common::Time gazebo::GazeboRosImuSensor::last_time
private

last time on which the data was published.

Definition at line 74 of file gazebo_ros_imu_sensor.h.

◆ node

ros::NodeHandle* gazebo::GazeboRosImuSensor::node
private

Ros NodeHandle pointer.

Definition at line 67 of file gazebo_ros_imu_sensor.h.

◆ offset

ignition::math::Pose3d gazebo::GazeboRosImuSensor::offset
private

Offset parameter, position part is unused.

Definition at line 100 of file gazebo_ros_imu_sensor.h.

◆ orientation

ignition::math::Quaterniond gazebo::GazeboRosImuSensor::orientation
private

Orientation data from the sensor.

Definition at line 82 of file gazebo_ros_imu_sensor.h.

◆ robot_namespace

std::string gazebo::GazeboRosImuSensor::robot_namespace
private

The data is published on the topic named: /robot_namespace/topic_name.

Definition at line 90 of file gazebo_ros_imu_sensor.h.

◆ sdf

sdf::ElementPtr gazebo::GazeboRosImuSensor::sdf
private

Pointer to the sdf config file.

Definition at line 80 of file gazebo_ros_imu_sensor.h.

◆ sensor

sensors::ImuSensor* gazebo::GazeboRosImuSensor::sensor
private

Pointer to the sensor.

Definition at line 78 of file gazebo_ros_imu_sensor.h.

◆ topic_name

std::string gazebo::GazeboRosImuSensor::topic_name
private

The data is published on the topic named: /robot_namespace/topic_name.

Definition at line 92 of file gazebo_ros_imu_sensor.h.

◆ update_rate

double gazebo::GazeboRosImuSensor::update_rate
private

Sensor update rate.

Definition at line 96 of file gazebo_ros_imu_sensor.h.


The documentation for this class was generated from the following files:


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28