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...
 
virtual ~GazeboRosIMU ()
 Destructor. More...
 

Protected Member Functions

virtual void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 
virtual void Reset ()
 
virtual void Update ()
 

Private Member Functions

double GaussianKernel (double mu, double sigma)
 Gaussian noise generator. More...
 
bool ServiceCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 call back when using service More...
 
bool SetAccelBiasCallback (hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res)
 Bias service callbacks. More...
 
bool SetRateBiasCallback (hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res)
 

Private Attributes

math::Vector3 accel
 
ros::ServiceServer accelBiasService
 
SensorModel3 accelModel
 Sensor models. More...
 
ros::Publisher bias_pub_
 
std::string bias_topic_
 
sensor_msgs::Imu biasMsg
 
boost::shared_ptr< dynamic_reconfigure::Server< SensorModelConfig > > dynamic_reconfigure_server_accel_
 
boost::shared_ptr< dynamic_reconfigure::Server< SensorModelConfig > > dynamic_reconfigure_server_rate_
 
boost::shared_ptr< dynamic_reconfigure::Server< SensorModelConfig > > dynamic_reconfigure_server_yaw_
 
std::string frame_id_
 frame id More...
 
math::Vector3 gravity
 
sensor_msgs::Imu imuMsg
 ros message More...
 
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...
 
std::string namespace_
 for setting ROS name space More...
 
ros::NodeHandlenode_handle_
 pointer to ros node More...
 
math::Pose offset_
 allow specifying constant xyz and rpy offsets More...
 
math::Quaternion orientation
 save current body/physics state More...
 
ros::Publisher pub_
 
math::Vector3 rate
 
ros::ServiceServer rateBiasService
 
SensorModel3 rateModel
 
std::string serviceName
 
ros::ServiceServer srv_
 
std::string topic_
 topic name More...
 
event::ConnectionPtr updateConnection
 
UpdateTimer updateTimer
 
math::Vector3 velocity
 
physics::WorldPtr world
 The parent World. More...
 
SensorModel yawModel
 

Detailed Description

Definition at line 52 of file gazebo_ros_imu.h.

Constructor & Destructor Documentation

gazebo::GazeboRosIMU::GazeboRosIMU ( )

Constructor.

Definition at line 46 of file gazebo_ros_imu.cpp.

gazebo::GazeboRosIMU::~GazeboRosIMU ( )
virtual

Destructor.

Definition at line 52 of file gazebo_ros_imu.cpp.

Member Function Documentation

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

Gaussian noise generator.

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

Definition at line 69 of file gazebo_ros_imu.cpp.

void gazebo::GazeboRosIMU::Reset ( )
protectedvirtual

Definition at line 227 of file gazebo_ros_imu.cpp.

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

call back when using service

Definition at line 246 of file gazebo_ros_imu.cpp.

bool gazebo::GazeboRosIMU::SetAccelBiasCallback ( hector_gazebo_plugins::SetBias::Request &  req,
hector_gazebo_plugins::SetBias::Response &  res 
)
private

Bias service callbacks.

Definition at line 258 of file gazebo_ros_imu.cpp.

bool gazebo::GazeboRosIMU::SetRateBiasCallback ( hector_gazebo_plugins::SetBias::Request &  req,
hector_gazebo_plugins::SetBias::Response &  res 
)
private

Definition at line 269 of file gazebo_ros_imu.cpp.

void gazebo::GazeboRosIMU::Update ( )
protectedvirtual

Definition at line 282 of file gazebo_ros_imu.cpp.

Member Data Documentation

math::Vector3 gazebo::GazeboRosIMU::accel
private

Definition at line 117 of file gazebo_ros_imu.h.

ros::ServiceServer gazebo::GazeboRosIMU::accelBiasService
private

Definition at line 137 of file gazebo_ros_imu.h.

SensorModel3 gazebo::GazeboRosIMU::accelModel
private

Sensor models.

Definition at line 100 of file gazebo_ros_imu.h.

ros::Publisher gazebo::GazeboRosIMU::bias_pub_
private

Definition at line 76 of file gazebo_ros_imu.h.

std::string gazebo::GazeboRosIMU::bias_topic_
private

Definition at line 90 of file gazebo_ros_imu.h.

sensor_msgs::Imu gazebo::GazeboRosIMU::biasMsg
private

Definition at line 80 of file gazebo_ros_imu.h.

boost::shared_ptr<dynamic_reconfigure::Server<SensorModelConfig> > gazebo::GazeboRosIMU::dynamic_reconfigure_server_accel_
private

Definition at line 149 of file gazebo_ros_imu.h.

boost::shared_ptr<dynamic_reconfigure::Server<SensorModelConfig> > gazebo::GazeboRosIMU::dynamic_reconfigure_server_rate_
private

Definition at line 149 of file gazebo_ros_imu.h.

boost::shared_ptr<dynamic_reconfigure::Server<SensorModelConfig> > gazebo::GazeboRosIMU::dynamic_reconfigure_server_yaw_
private

Definition at line 149 of file gazebo_ros_imu.h.

std::string gazebo::GazeboRosIMU::frame_id_
private

frame id

Definition at line 86 of file gazebo_ros_imu.h.

math::Vector3 gazebo::GazeboRosIMU::gravity
private

Definition at line 119 of file gazebo_ros_imu.h.

sensor_msgs::Imu gazebo::GazeboRosIMU::imuMsg
private

ros message

Definition at line 79 of file gazebo_ros_imu.h.

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

The link referred to by this plugin.

Definition at line 71 of file gazebo_ros_imu.h.

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

store link name

Definition at line 83 of file gazebo_ros_imu.h.

boost::mutex gazebo::GazeboRosIMU::lock
private

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

Definition at line 105 of file gazebo_ros_imu.h.

std::string gazebo::GazeboRosIMU::namespace_
private

for setting ROS name space

Definition at line 126 of file gazebo_ros_imu.h.

ros::NodeHandle* gazebo::GazeboRosIMU::node_handle_
private

pointer to ros node

Definition at line 74 of file gazebo_ros_imu.h.

math::Pose gazebo::GazeboRosIMU::offset_
private

allow specifying constant xyz and rpy offsets

Definition at line 96 of file gazebo_ros_imu.h.

math::Quaternion gazebo::GazeboRosIMU::orientation
private

save current body/physics state

Definition at line 115 of file gazebo_ros_imu.h.

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

Definition at line 75 of file gazebo_ros_imu.h.

math::Vector3 gazebo::GazeboRosIMU::rate
private

Definition at line 118 of file gazebo_ros_imu.h.

ros::ServiceServer gazebo::GazeboRosIMU::rateBiasService
private

Definition at line 138 of file gazebo_ros_imu.h.

SensorModel3 gazebo::GazeboRosIMU::rateModel
private

Definition at line 101 of file gazebo_ros_imu.h.

std::string gazebo::GazeboRosIMU::serviceName
private

Definition at line 132 of file gazebo_ros_imu.h.

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

Definition at line 131 of file gazebo_ros_imu.h.

std::string gazebo::GazeboRosIMU::topic_
private

topic name

Definition at line 89 of file gazebo_ros_imu.h.

event::ConnectionPtr gazebo::GazeboRosIMU::updateConnection
private

Definition at line 147 of file gazebo_ros_imu.h.

UpdateTimer gazebo::GazeboRosIMU::updateTimer
private

Definition at line 146 of file gazebo_ros_imu.h.

math::Vector3 gazebo::GazeboRosIMU::velocity
private

Definition at line 116 of file gazebo_ros_imu.h.

physics::WorldPtr gazebo::GazeboRosIMU::world
private

The parent World.

Definition at line 68 of file gazebo_ros_imu.h.

SensorModel gazebo::GazeboRosIMU::yawModel
private

Definition at line 102 of file gazebo_ros_imu.h.


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


hector_gazebo_plugins
Author(s): Stefan Kohlbrecher , Johannes Meyer
autogenerated on Wed Jun 5 2019 22:40:23