$search

gazebo::GazeboRosIMU Class Reference
[Groud Truth Position Pose and Rates Interface]

GazeboRosIMU controller. More...

#include <gazebo_ros_imu.h>

List of all members.

Public Member Functions

 GazeboRosIMU (Entity *parent)
 Constructor.
virtual ~GazeboRosIMU ()
 Destructor.

Protected Member Functions

virtual void FiniChild ()
 Finalize the controller.
virtual void InitChild ()
 Init the controller.
virtual void LoadChild (XMLConfigNode *node)
 Load the controller.
virtual void UpdateChild ()
 Update the controller.

Private Member Functions

void DeprecatedIMUConnect ()
void DeprecatedIMUDisconnect ()
double GaussianKernel (double mu, double sigma)
 Gaussian noise generator.
void IMUConnect ()
void IMUDisconnect ()
bool ServiceCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 call back when using service

Private Attributes

Vector3 aeul
Vector3 apos
std::string bodyName
ParamT< std::string > * bodyNameP
 store bodyname
ros::Publisher deprecated_pub_
int deprecatedImuConnectCount
std::string deprecatedTopicName
ParamT< std::string > * deprecatedTopicNameP
ParamT< std::string > * frameNameP
 frame transform name, should match link name deprecating this field for imu blocks. give warning and explaination if this is specified
double gaussianNoise
ParamT< double > * gaussianNoiseP
 Gaussian noise.
int imuConnectCount
 Keep track of number of connctions.
sensor_msgs::Imu imuMsg
 ros message
Pose3d initial_pose
Time last_time
 save last_time
Vector3 last_veul
Vector3 last_vpos
boost::mutex lock
 A mutex to lock access to fields that are used in message callbacks.
Body * myBody
 The parent Model.
Model * myParent
 The parent Model.
ros::Publisher pub_
std::string robotNamespace
ParamT< std::string > * robotNamespaceP
 for setting ROS name space
ros::NodeHandlerosnode_
 pointer to ros node
Vector3 rpyOffsets
ParamT< Vector3 > * rpyOffsetsP
std::string serviceName
ParamT< std::string > * serviceNameP
ros::ServiceServer srv_
std::string topicName
ParamT< std::string > * topicNameP
 topic name
Vector3 xyzOffsets
ParamT< Vector3 > * xyzOffsetsP
 allow specifying constant xyz and rpy offsets

Detailed Description

GazeboRosIMU controller.

Definition at line 99 of file gazebo_ros_imu.h.


Constructor & Destructor Documentation

GazeboRosIMU::GazeboRosIMU ( Entity *  parent  ) 

Constructor.

Definition at line 46 of file gazebo_ros_imu.cpp.

GazeboRosIMU::~GazeboRosIMU (  )  [virtual]

Destructor.

Definition at line 72 of file gazebo_ros_imu.cpp.


Member Function Documentation

void GazeboRosIMU::DeprecatedIMUConnect (  )  [private]

Definition at line 186 of file gazebo_ros_imu.cpp.

void GazeboRosIMU::DeprecatedIMUDisconnect (  )  [private]

Definition at line 194 of file gazebo_ros_imu.cpp.

void GazeboRosIMU::FiniChild (  )  [protected, virtual]

Finalize the controller.

Definition at line 328 of file gazebo_ros_imu.cpp.

double GazeboRosIMU::GaussianKernel ( double  mu,
double  sigma 
) [private]

Gaussian noise generator.

Definition at line 336 of file gazebo_ros_imu.cpp.

void GazeboRosIMU::IMUConnect (  )  [private]

Definition at line 173 of file gazebo_ros_imu.cpp.

void GazeboRosIMU::IMUDisconnect (  )  [private]

Definition at line 179 of file gazebo_ros_imu.cpp.

void GazeboRosIMU::InitChild (  )  [protected, virtual]

Init the controller.

Definition at line 202 of file gazebo_ros_imu.cpp.

void GazeboRosIMU::LoadChild ( XMLConfigNode *  node  )  [protected, virtual]

Load the controller.

Parameters:
node XML config node

Definition at line 88 of file gazebo_ros_imu.cpp.

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

call back when using service

Definition at line 165 of file gazebo_ros_imu.cpp.

void GazeboRosIMU::UpdateChild (  )  [protected, virtual]

Update the controller.

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

Definition at line 218 of file gazebo_ros_imu.cpp.


Member Data Documentation

Definition at line 163 of file gazebo_ros_imu.h.

Definition at line 162 of file gazebo_ros_imu.h.

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

Definition at line 136 of file gazebo_ros_imu.h.

ParamT<std::string>* gazebo::GazeboRosIMU::bodyNameP [private]

store bodyname

Definition at line 135 of file gazebo_ros_imu.h.

Definition at line 129 of file gazebo_ros_imu.h.

Definition at line 181 of file gazebo_ros_imu.h.

Definition at line 147 of file gazebo_ros_imu.h.

ParamT<std::string>* gazebo::GazeboRosIMU::deprecatedTopicNameP [private]

Definition at line 146 of file gazebo_ros_imu.h.

ParamT<std::string>* gazebo::GazeboRosIMU::frameNameP [private]

frame transform name, should match link name deprecating this field for imu blocks. give warning and explaination if this is specified

Definition at line 141 of file gazebo_ros_imu.h.

Definition at line 168 of file gazebo_ros_imu.h.

ParamT<double>* gazebo::GazeboRosIMU::gaussianNoiseP [private]

Gaussian noise.

Definition at line 167 of file gazebo_ros_imu.h.

Keep track of number of connctions.

Definition at line 178 of file gazebo_ros_imu.h.

ros message

Definition at line 132 of file gazebo_ros_imu.h.

Definition at line 164 of file gazebo_ros_imu.h.

save last_time

Definition at line 159 of file gazebo_ros_imu.h.

Definition at line 161 of file gazebo_ros_imu.h.

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

The parent Model.

Definition at line 124 of file gazebo_ros_imu.h.

The parent Model.

Definition at line 121 of file gazebo_ros_imu.h.

Definition at line 128 of file gazebo_ros_imu.h.

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

Definition at line 175 of file gazebo_ros_imu.h.

ParamT<std::string>* gazebo::GazeboRosIMU::robotNamespaceP [private]

for setting ROS name space

Definition at line 174 of file gazebo_ros_imu.h.

pointer to ros node

Definition at line 127 of file gazebo_ros_imu.h.

Definition at line 153 of file gazebo_ros_imu.h.

Definition at line 152 of file gazebo_ros_imu.h.

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

Definition at line 190 of file gazebo_ros_imu.h.

ParamT<std::string>* gazebo::GazeboRosIMU::serviceNameP [private]

Definition at line 189 of file gazebo_ros_imu.h.

Definition at line 188 of file gazebo_ros_imu.h.

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

Definition at line 145 of file gazebo_ros_imu.h.

ParamT<std::string>* gazebo::GazeboRosIMU::topicNameP [private]

topic name

Definition at line 144 of file gazebo_ros_imu.h.

Definition at line 151 of file gazebo_ros_imu.h.

allow specifying constant xyz and rpy offsets

Definition at line 150 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 Properties Friends Defines


gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Sat Mar 2 13:40:08 2013