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

#include <gazebo_ros_imu.h>

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

Public Member Functions

 GazeboRosIMU ()
 Constructor. More...
 
void Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf)
 Load the controller. More...
 
virtual ~GazeboRosIMU ()
 Destructor. More...
 

Protected Member Functions

virtual void UpdateChild ()
 Update the controller. More...
 

Private Member Functions

double GaussianKernel (double mu, double sigma)
 Gaussian noise generator. More...
 
void IMUQueueThread ()
 
void LoadThread ()
 
bool ServiceCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 call back when using service More...
 

Private Attributes

ignition::math::Vector3d aeul_
 
ignition::math::Vector3d apos_
 
boost::thread callback_queue_thread_
 
boost::thread deferred_load_thread_
 
std::string frame_name_
 store frame name More...
 
double gaussian_noise_
 Gaussian noise. More...
 
sensor_msgs::Imu imu_msg_
 ros message More...
 
ros::CallbackQueue imu_queue_
 
ignition::math::Pose3d initial_pose_
 : keep initial pose to offset orientation in imu message More...
 
common::Time last_time_
 save last_time More...
 
ignition::math::Vector3d last_veul_
 
ignition::math::Vector3d last_vpos_
 
physics::LinkPtr link
 The link referred to by this plugin. More...
 
std::string link_name_
 store link name More...
 
boost::mutex lock_
 A mutex to lock access to fields that are used in message callbacks. More...
 
ignition::math::Pose3d offset_
 allow specifying constant xyz and rpy offsets More...
 
PubMultiQueue pmq
 
ros::Publisher pub_
 
PubQueue< sensor_msgs::Imu >::Ptr pub_Queue
 
std::string robot_namespace_
 for setting ROS name space More...
 
ros::NodeHandlerosnode_
 pointer to ros node More...
 
sdf::ElementPtr sdf
 
std::string service_name_
 
ros::ServiceServer srv_
 
std::string topic_name_
 topic name More...
 
event::ConnectionPtr update_connection_
 
double update_rate_
 
physics::WorldPtr world_
 The parent World. More...
 

Detailed Description

Definition at line 39 of file gazebo_ros_imu.h.

Constructor & Destructor Documentation

◆ GazeboRosIMU()

gazebo::GazeboRosIMU::GazeboRosIMU ( )

Constructor.

Definition at line 36 of file gazebo_ros_imu.cpp.

◆ ~GazeboRosIMU()

gazebo::GazeboRosIMU::~GazeboRosIMU ( )
virtual

Destructor.

Definition at line 42 of file gazebo_ros_imu.cpp.

Member Function Documentation

◆ GaussianKernel()

double gazebo::GazeboRosIMU::GaussianKernel ( double  mu,
double  sigma 
)
private

Gaussian noise generator.

Definition at line 352 of file gazebo_ros_imu.cpp.

◆ IMUQueueThread()

void gazebo::GazeboRosIMU::IMUQueueThread ( )
private

Definition at line 374 of file gazebo_ros_imu.cpp.

◆ Load()

void gazebo::GazeboRosIMU::Load ( physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
)

Load the controller.

Parameters
nodeXML config node

Definition at line 53 of file gazebo_ros_imu.cpp.

◆ LoadThread()

void gazebo::GazeboRosIMU::LoadThread ( )
private

Definition at line 66 of file gazebo_ros_imu.cpp.

◆ ServiceCallback()

bool gazebo::GazeboRosIMU::ServiceCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)
private

call back when using service

Definition at line 212 of file gazebo_ros_imu.cpp.

◆ UpdateChild()

void gazebo::GazeboRosIMU::UpdateChild ( )
protectedvirtual

Update the controller.

Todo:
: let user set separate linear and angular covariance values.
Todo:
: apply appropriate rotations from frame_pose

Definition at line 220 of file gazebo_ros_imu.cpp.

Member Data Documentation

◆ aeul_

ignition::math::Vector3d gazebo::GazeboRosIMU::aeul_
private

Definition at line 89 of file gazebo_ros_imu.h.

◆ apos_

ignition::math::Vector3d gazebo::GazeboRosIMU::apos_
private

Definition at line 88 of file gazebo_ros_imu.h.

◆ callback_queue_thread_

boost::thread gazebo::GazeboRosIMU::callback_queue_thread_
private

Definition at line 115 of file gazebo_ros_imu.h.

◆ deferred_load_thread_

boost::thread gazebo::GazeboRosIMU::deferred_load_thread_
private

Definition at line 123 of file gazebo_ros_imu.h.

◆ frame_name_

std::string gazebo::GazeboRosIMU::frame_name_
private

store frame name

Definition at line 72 of file gazebo_ros_imu.h.

◆ gaussian_noise_

double gazebo::GazeboRosIMU::gaussian_noise_
private

Gaussian noise.

Definition at line 98 of file gazebo_ros_imu.h.

◆ imu_msg_

sensor_msgs::Imu gazebo::GazeboRosIMU::imu_msg_
private

ros message

Definition at line 66 of file gazebo_ros_imu.h.

◆ imu_queue_

ros::CallbackQueue gazebo::GazeboRosIMU::imu_queue_
private

Definition at line 113 of file gazebo_ros_imu.h.

◆ initial_pose_

ignition::math::Pose3d gazebo::GazeboRosIMU::initial_pose_
private

: keep initial pose to offset orientation in imu message

Definition at line 95 of file gazebo_ros_imu.h.

◆ last_time_

common::Time gazebo::GazeboRosIMU::last_time_
private

save last_time

Definition at line 85 of file gazebo_ros_imu.h.

◆ last_veul_

ignition::math::Vector3d gazebo::GazeboRosIMU::last_veul_
private

Definition at line 87 of file gazebo_ros_imu.h.

◆ last_vpos_

ignition::math::Vector3d gazebo::GazeboRosIMU::last_vpos_
private

Definition at line 86 of file gazebo_ros_imu.h.

◆ link

physics::LinkPtr gazebo::GazeboRosIMU::link
private

The link referred to by this plugin.

Definition at line 58 of file gazebo_ros_imu.h.

◆ link_name_

std::string gazebo::GazeboRosIMU::link_name_
private

store link name

Definition at line 69 of file gazebo_ros_imu.h.

◆ lock_

boost::mutex gazebo::GazeboRosIMU::lock_
private

A mutex to lock access to fields that are used in message callbacks.

Definition at line 82 of file gazebo_ros_imu.h.

◆ offset_

ignition::math::Pose3d gazebo::GazeboRosIMU::offset_
private

allow specifying constant xyz and rpy offsets

Definition at line 78 of file gazebo_ros_imu.h.

◆ pmq

PubMultiQueue gazebo::GazeboRosIMU::pmq
private

Definition at line 126 of file gazebo_ros_imu.h.

◆ pub_

ros::Publisher gazebo::GazeboRosIMU::pub_
private

Definition at line 62 of file gazebo_ros_imu.h.

◆ pub_Queue

PubQueue<sensor_msgs::Imu>::Ptr gazebo::GazeboRosIMU::pub_Queue
private

Definition at line 63 of file gazebo_ros_imu.h.

◆ robot_namespace_

std::string gazebo::GazeboRosIMU::robot_namespace_
private

for setting ROS name space

Definition at line 104 of file gazebo_ros_imu.h.

◆ rosnode_

ros::NodeHandle* gazebo::GazeboRosIMU::rosnode_
private

pointer to ros node

Definition at line 61 of file gazebo_ros_imu.h.

◆ sdf

sdf::ElementPtr gazebo::GazeboRosIMU::sdf
private

Definition at line 121 of file gazebo_ros_imu.h.

◆ service_name_

std::string gazebo::GazeboRosIMU::service_name_
private

Definition at line 111 of file gazebo_ros_imu.h.

◆ srv_

ros::ServiceServer gazebo::GazeboRosIMU::srv_
private

Definition at line 110 of file gazebo_ros_imu.h.

◆ topic_name_

std::string gazebo::GazeboRosIMU::topic_name_
private

topic name

Definition at line 75 of file gazebo_ros_imu.h.

◆ update_connection_

event::ConnectionPtr gazebo::GazeboRosIMU::update_connection_
private

Definition at line 118 of file gazebo_ros_imu.h.

◆ update_rate_

double gazebo::GazeboRosIMU::update_rate_
private

Definition at line 92 of file gazebo_ros_imu.h.

◆ world_

physics::WorldPtr gazebo::GazeboRosIMU::world_
private

The parent World.

Definition at line 55 of file gazebo_ros_imu.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