$search

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

GazeboRosP3D controller. More...

#include <gazebo_ros_p3d.h>

List of all members.

Public Member Functions

 GazeboRosP3D (Entity *parent)
 Constructor.
virtual ~GazeboRosP3D ()
 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

double GaussianKernel (double mu, double sigma)
 Gaussian noise generator.
void P3DConnect ()
void P3DDisconnect ()

Private Attributes

Vector3 aeul
Vector3 apos
std::string bodyName
ParamT< std::string > * bodyNameP
 store bodyname
Vector3 frame_aeul
Vector3 frame_apos
std::string frameName
ParamT< std::string > * frameNameP
 frame transform name, should match link name FIXME: extract link name directly?
double gaussianNoise
ParamT< double > * gaussianNoiseP
 Gaussian noise.
Pose3d initial_frame_pose
Vector3 last_frame_veul
Vector3 last_frame_vpos
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.
Body * myFrame
 The body of the frame to display pose, twist.
Model * myParent
 The parent Model.
int p3dConnectCount
 Keep track of number of connctions.
nav_msgs::Odometry poseMsg
 ros message
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 topicName
ParamT< std::string > * topicNameP
 topic name
Vector3 xyzOffsets
ParamT< Vector3 > * xyzOffsetsP
 allow specifying constant xyz and rpy offsets

Detailed Description

GazeboRosP3D controller.

Definition at line 99 of file gazebo_ros_p3d.h.


Constructor & Destructor Documentation

GazeboRosP3D::GazeboRosP3D ( Entity *  parent  ) 

Constructor.

Definition at line 47 of file gazebo_ros_p3d.cpp.

GazeboRosP3D::~GazeboRosP3D (  )  [virtual]

Destructor.

Definition at line 70 of file gazebo_ros_p3d.cpp.


Member Function Documentation

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

Finalize the controller.

Definition at line 337 of file gazebo_ros_p3d.cpp.

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

Gaussian noise generator.

Definition at line 351 of file gazebo_ros_p3d.cpp.

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

Init the controller.

Definition at line 152 of file gazebo_ros_p3d.cpp.

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

Load the controller.

Parameters:
node XML config node

Definition at line 84 of file gazebo_ros_p3d.cpp.

void GazeboRosP3D::P3DConnect (  )  [private]

Definition at line 139 of file gazebo_ros_p3d.cpp.

void GazeboRosP3D::P3DDisconnect (  )  [private]

Definition at line 145 of file gazebo_ros_p3d.cpp.

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

Update the controller.

if frameName specified is "world", "/map" or "map" report back inertial values in the gazebo world

Todo:
: let user set separate linear and angular covariance values.

Definition at line 177 of file gazebo_ros_p3d.cpp.


Member Data Documentation

Definition at line 164 of file gazebo_ros_p3d.h.

Definition at line 163 of file gazebo_ros_p3d.h.

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

Definition at line 139 of file gazebo_ros_p3d.h.

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

store bodyname

Definition at line 138 of file gazebo_ros_p3d.h.

Definition at line 168 of file gazebo_ros_p3d.h.

Definition at line 167 of file gazebo_ros_p3d.h.

std::string gazebo::GazeboRosP3D::frameName [private]

Definition at line 148 of file gazebo_ros_p3d.h.

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

frame transform name, should match link name FIXME: extract link name directly?

Definition at line 147 of file gazebo_ros_p3d.h.

Definition at line 173 of file gazebo_ros_p3d.h.

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

Gaussian noise.

Definition at line 172 of file gazebo_ros_p3d.h.

Definition at line 169 of file gazebo_ros_p3d.h.

Definition at line 166 of file gazebo_ros_p3d.h.

Definition at line 165 of file gazebo_ros_p3d.h.

save last_time

Definition at line 160 of file gazebo_ros_p3d.h.

Definition at line 162 of file gazebo_ros_p3d.h.

Definition at line 161 of file gazebo_ros_p3d.h.

boost::mutex gazebo::GazeboRosP3D::lock [private]

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

Definition at line 157 of file gazebo_ros_p3d.h.

The parent Model.

Definition at line 124 of file gazebo_ros_p3d.h.

The body of the frame to display pose, twist.

Definition at line 127 of file gazebo_ros_p3d.h.

The parent Model.

Definition at line 121 of file gazebo_ros_p3d.h.

Keep track of number of connctions.

Definition at line 183 of file gazebo_ros_p3d.h.

ros message

Definition at line 135 of file gazebo_ros_p3d.h.

Definition at line 132 of file gazebo_ros_p3d.h.

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

Definition at line 180 of file gazebo_ros_p3d.h.

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

for setting ROS name space

Definition at line 179 of file gazebo_ros_p3d.h.

pointer to ros node

Definition at line 131 of file gazebo_ros_p3d.h.

Definition at line 154 of file gazebo_ros_p3d.h.

Definition at line 153 of file gazebo_ros_p3d.h.

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

Definition at line 143 of file gazebo_ros_p3d.h.

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

topic name

Definition at line 142 of file gazebo_ros_p3d.h.

Definition at line 152 of file gazebo_ros_p3d.h.

allow specifying constant xyz and rpy offsets

Definition at line 151 of file gazebo_ros_p3d.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