All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends
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.
std::string frameId
 frame id
math::Vector3 gravity
math::Vector3 gravity_body
SensorModel headingModel
sensor_msgs::Imu imuMsg
 ros message
common::Time last_time
 save last_time
physics::LinkPtr link
 The link referred to by this plugin.
std::string linkName
 store link name
boost::mutex lock
 A mutex to lock access to fields that are used in message callbacks.
ros::NodeHandle * node_handle_
 pointer to ros node
math::Quaternion orientation
 save current body/physics state
ros::Publisher pub_
math::Vector3 rate
ros::ServiceServer rateBiasService
SensorModel3 rateModel
std::string robotNamespace
 for setting ROS name space
std::string serviceName
ros::ServiceServer srv_
std::string topicName
 topic name
common::Time update_period
event::ConnectionPtr updateConnection
math::Vector3 velocity
physics::WorldPtr world
 The parent World.

Detailed Description

Definition at line 78 of file gazebo_ros_imu.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 72 of file gazebo_ros_imu.cpp.

Destructor.

Definition at line 78 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 91 of file gazebo_ros_imu.cpp.

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

Definition at line 205 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 219 of file gazebo_ros_imu.cpp.

Bias service callbacks.

Definition at line 227 of file gazebo_ros_imu.cpp.

Definition at line 234 of file gazebo_ros_imu.cpp.

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

Definition at line 243 of file gazebo_ros_imu.cpp.


Member Data Documentation

math::Vector3 gazebo::GazeboRosIMU::accel [private]

Definition at line 130 of file gazebo_ros_imu.h.

ros::ServiceServer gazebo::GazeboRosIMU::accelBiasService [private]

Definition at line 150 of file gazebo_ros_imu.h.

Sensor models.

Definition at line 116 of file gazebo_ros_imu.h.

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

frame id

Definition at line 110 of file gazebo_ros_imu.h.

math::Vector3 gazebo::GazeboRosIMU::gravity [private]

Definition at line 132 of file gazebo_ros_imu.h.

math::Vector3 gazebo::GazeboRosIMU::gravity_body [private]

Definition at line 133 of file gazebo_ros_imu.h.

Definition at line 118 of file gazebo_ros_imu.h.

sensor_msgs::Imu gazebo::GazeboRosIMU::imuMsg [private]

ros message

Definition at line 104 of file gazebo_ros_imu.h.

common::Time gazebo::GazeboRosIMU::last_time [private]

save last_time

Definition at line 124 of file gazebo_ros_imu.h.

physics::LinkPtr gazebo::GazeboRosIMU::link [private]

The link referred to by this plugin.

Definition at line 97 of file gazebo_ros_imu.h.

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

store link name

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

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

pointer to ros node

Definition at line 100 of file gazebo_ros_imu.h.

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

save current body/physics state

Definition at line 128 of file gazebo_ros_imu.h.

ros::Publisher gazebo::GazeboRosIMU::pub_ [private]

Definition at line 101 of file gazebo_ros_imu.h.

math::Vector3 gazebo::GazeboRosIMU::rate [private]

Definition at line 131 of file gazebo_ros_imu.h.

ros::ServiceServer gazebo::GazeboRosIMU::rateBiasService [private]

Definition at line 151 of file gazebo_ros_imu.h.

Definition at line 117 of file gazebo_ros_imu.h.

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

for setting ROS name space

Definition at line 139 of file gazebo_ros_imu.h.

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

Definition at line 145 of file gazebo_ros_imu.h.

ros::ServiceServer gazebo::GazeboRosIMU::srv_ [private]

Definition at line 144 of file gazebo_ros_imu.h.

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

topic name

Definition at line 113 of file gazebo_ros_imu.h.

common::Time gazebo::GazeboRosIMU::update_period [private]

Definition at line 125 of file gazebo_ros_imu.h.

event::ConnectionPtr gazebo::GazeboRosIMU::updateConnection [private]

Definition at line 160 of file gazebo_ros_imu.h.

math::Vector3 gazebo::GazeboRosIMU::velocity [private]

Definition at line 129 of file gazebo_ros_imu.h.

physics::WorldPtr gazebo::GazeboRosIMU::world [private]

The parent World.

Definition at line 94 of file gazebo_ros_imu.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


hector_gazebo_plugins
Author(s): Stefan Kohlbrecher and Johannes Meyer
autogenerated on Mon Dec 24 2012 16:49:46