Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
gazebo::GazeboRosIMU Class Reference

#include <gazebo_ros_imu.h>

List of all members.

Public Member Functions

 GazeboRosIMU ()
 Constructor.
virtual ~GazeboRosIMU ()
 Destructor.

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.
bool ServiceCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 call back when using service
bool SetAccelBiasCallback (hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res)
 Bias service callbacks.
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.
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
math::Vector3 gravity
sensor_msgs::Imu imuMsg
 ros message
physics::LinkPtr link
 The link referred to by this plugin.
std::string link_name_
 store link name
boost::mutex lock
 A mutex to lock access to fields that are used in message callbacks.
std::string namespace_
 for setting ROS name space
ros::NodeHandlenode_handle_
 pointer to ros node
math::Pose offset_
 allow specifying constant xyz and rpy offsets
math::Quaternion orientation
 save current body/physics state
ros::Publisher pub_
math::Vector3 rate
ros::ServiceServer rateBiasService
SensorModel3 rateModel
std::string serviceName
ros::ServiceServer srv_
std::string topic_
 topic name
event::ConnectionPtr updateConnection
UpdateTimer updateTimer
math::Vector3 velocity
physics::WorldPtr world
 The parent World.
SensorModel yawModel

Detailed Description

Definition at line 52 of file gazebo_ros_imu.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 46 of file gazebo_ros_imu.cpp.

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 
) [protected, virtual]

Definition at line 69 of file gazebo_ros_imu.cpp.

void gazebo::GazeboRosIMU::Reset ( ) [protected, virtual]

Definition at line 202 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 217 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 225 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 232 of file gazebo_ros_imu.cpp.

void gazebo::GazeboRosIMU::Update ( ) [protected, virtual]

Definition at line 241 of file gazebo_ros_imu.cpp.


Member Data Documentation

Definition at line 106 of file gazebo_ros_imu.h.

Definition at line 125 of file gazebo_ros_imu.h.

Sensor models.

Definition at line 96 of file gazebo_ros_imu.h.

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 137 of file gazebo_ros_imu.h.

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

Definition at line 137 of file gazebo_ros_imu.h.

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

Definition at line 137 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.

Definition at line 108 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 101 of file gazebo_ros_imu.h.

std::string gazebo::GazeboRosIMU::namespace_ [private]

for setting ROS name space

Definition at line 114 of file gazebo_ros_imu.h.

pointer to ros node

Definition at line 74 of file gazebo_ros_imu.h.

allow specifying constant xyz and rpy offsets

Definition at line 93 of file gazebo_ros_imu.h.

math::Quaternion gazebo::GazeboRosIMU::orientation [private]

save current body/physics state

Definition at line 104 of file gazebo_ros_imu.h.

Definition at line 75 of file gazebo_ros_imu.h.

Definition at line 107 of file gazebo_ros_imu.h.

Definition at line 126 of file gazebo_ros_imu.h.

Definition at line 97 of file gazebo_ros_imu.h.

std::string gazebo::GazeboRosIMU::serviceName [private]

Definition at line 120 of file gazebo_ros_imu.h.

Definition at line 119 of file gazebo_ros_imu.h.

std::string gazebo::GazeboRosIMU::topic_ [private]

topic name

Definition at line 89 of file gazebo_ros_imu.h.

Definition at line 135 of file gazebo_ros_imu.h.

Definition at line 134 of file gazebo_ros_imu.h.

Definition at line 105 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.

Definition at line 98 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 Mon Jun 27 2016 04:58:09