$search

gazebo::GazeboRosStepWorldState Class Reference
[GazeboRosStepWorldState]

#include <gazebo_ros_step_world_state.h>

List of all members.

Public Member Functions

 GazeboRosStepWorldState (Entity *parent)
 Constructor.
virtual ~GazeboRosStepWorldState ()
 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 QueueThread ()
void WorldStateCallback (const gazebo_msgs::WorldStateConstPtr &worldStateMsg)

Private Attributes

std::map< std::string,
gazebo::Body * > 
all_bodies
 : keep list of all bodies in the world (across models)
const std::map< std::string,
gazebo::Body * > * 
bodies
 : Keep list of all models in the world
boost::thread callback_queue_thread_
std::string frameName
ParamT< std::string > * frameNameP
 frame transform name, should match link name
std::vector< gazebo::Model * > models
 : keep list of all models in the world
gazebo::Model * parent_model_
 : parent should be a model
ros::CallbackQueue queue_
std::string robotNamespace
ParamT< std::string > * robotNamespaceP
 for setting ROS name space
ros::NodeHandlerosnode_
 : ros node handle and publisher
ros::Subscriber sub_
std::string topicName
ParamT< std::string > * topicNameP
 topic name
gazebo_msgs::WorldState worldStateMsg
 : Message for sending world state

Detailed Description

Definition at line 68 of file gazebo_ros_step_world_state.h.


Constructor & Destructor Documentation

GazeboRosStepWorldState::GazeboRosStepWorldState ( Entity *  parent  ) 

Constructor.

Parameters:
parent The parent entity, must be a Model or a Sensor

Definition at line 49 of file gazebo_ros_step_world_state.cpp.

GazeboRosStepWorldState::~GazeboRosStepWorldState (  )  [virtual]

Destructor.

Definition at line 69 of file gazebo_ros_step_world_state.cpp.


Member Function Documentation

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

Finalize the controller.

Definition at line 192 of file gazebo_ros_step_world_state.cpp.

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

Init the controller.

Definition at line 146 of file gazebo_ros_step_world_state.cpp.

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

Load the controller.

Parameters:
node XML config node

Definition at line 79 of file gazebo_ros_step_world_state.cpp.

void GazeboRosStepWorldState::QueueThread (  )  [private]

Definition at line 204 of file gazebo_ros_step_world_state.cpp.

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

Update the controller.

Definition at line 154 of file gazebo_ros_step_world_state.cpp.

void GazeboRosStepWorldState::WorldStateCallback ( const gazebo_msgs::WorldStateConstPtr worldStateMsg  )  [private]

Definition at line 108 of file gazebo_ros_step_world_state.cpp.


Member Data Documentation

std::map<std::string,gazebo::Body*> gazebo::GazeboRosStepWorldState::all_bodies [private]

: keep list of all bodies in the world (across models)

Definition at line 103 of file gazebo_ros_step_world_state.h.

const std::map<std::string,gazebo::Body*>* gazebo::GazeboRosStepWorldState::bodies [private]

: Keep list of all models in the world

Definition at line 94 of file gazebo_ros_step_world_state.h.

Definition at line 125 of file gazebo_ros_step_world_state.h.

Definition at line 120 of file gazebo_ros_step_world_state.h.

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

frame transform name, should match link name

Definition at line 119 of file gazebo_ros_step_world_state.h.

std::vector<gazebo::Model*> gazebo::GazeboRosStepWorldState::models [private]

: keep list of all models in the world

Definition at line 100 of file gazebo_ros_step_world_state.h.

: parent should be a model

Definition at line 97 of file gazebo_ros_step_world_state.h.

Definition at line 123 of file gazebo_ros_step_world_state.h.

Definition at line 112 of file gazebo_ros_step_world_state.h.

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

for setting ROS name space

Definition at line 111 of file gazebo_ros_step_world_state.h.

: ros node handle and publisher

Definition at line 106 of file gazebo_ros_step_world_state.h.

Definition at line 107 of file gazebo_ros_step_world_state.h.

Definition at line 116 of file gazebo_ros_step_world_state.h.

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

topic name

Definition at line 115 of file gazebo_ros_step_world_state.h.

: Message for sending world state

Definition at line 91 of file gazebo_ros_step_world_state.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