#include <gazebo_ros_pub_world_state.h>
Public Member Functions | |
| GazeboRosPubWorldState (Entity *parent) | |
| Constructor. | |
| virtual | ~GazeboRosPubWorldState () |
| 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 | WorldStateConnect () |
| void | WorldStateDisconnect () |
Private Attributes | |
| boost::thread | callback_queue_thread_ |
| std::string | frameName |
| ParamT< std::string > * | frameNameP |
| frame transform name, should match link name | |
| boost::mutex | lock |
| A mutex to lock access to fields that are used in message callbacks. | |
| gazebo::Model * | parent_model_ |
| : parent should be a model | |
| ros::Publisher | pub_ |
| ros::CallbackQueue | queue_ |
| std::string | robotNamespace |
| ParamT< std::string > * | robotNamespaceP |
| for setting ROS name space | |
| ros::NodeHandle * | rosnode_ |
| : ros node handle and publisher | |
| std::string | topicName |
| ParamT< std::string > * | topicNameP |
| topic name | |
| int | worldStateConnectCount |
| : keep track of number of connections | |
| gazebo_plugins::WorldState | worldStateMsg |
| : Message for sending world state | |
Definition at line 96 of file gazebo_ros_pub_world_state.h.
| GazeboRosPubWorldState::GazeboRosPubWorldState | ( | Entity * | parent | ) |
Constructor.
| parent | The parent entity, must be a Model or a Sensor |
Definition at line 47 of file gazebo_ros_pub_world_state.cpp.
| GazeboRosPubWorldState::~GazeboRosPubWorldState | ( | ) | [virtual] |
Destructor.
Definition at line 66 of file gazebo_ros_pub_world_state.cpp.
| void GazeboRosPubWorldState::FiniChild | ( | ) | [protected, virtual] |
Finalize the controller.
Definition at line 252 of file gazebo_ros_pub_world_state.cpp.
| void GazeboRosPubWorldState::InitChild | ( | ) | [protected, virtual] |
Init the controller.
Definition at line 120 of file gazebo_ros_pub_world_state.cpp.
| void GazeboRosPubWorldState::LoadChild | ( | XMLConfigNode * | node | ) | [protected, virtual] |
Load the controller.
| node | XML config node |
Definition at line 76 of file gazebo_ros_pub_world_state.cpp.
| void GazeboRosPubWorldState::QueueThread | ( | ) | [private] |
Definition at line 265 of file gazebo_ros_pub_world_state.cpp.
| void GazeboRosPubWorldState::UpdateChild | ( | ) | [protected, virtual] |
Update the controller.
: list of all models in the world
: list of all bodies in the model
Definition at line 128 of file gazebo_ros_pub_world_state.cpp.
| void GazeboRosPubWorldState::WorldStateConnect | ( | ) | [private] |
Definition at line 106 of file gazebo_ros_pub_world_state.cpp.
| void GazeboRosPubWorldState::WorldStateDisconnect | ( | ) | [private] |
Definition at line 113 of file gazebo_ros_pub_world_state.cpp.
boost::thread gazebo::GazeboRosPubWorldState::callback_queue_thread_ [private] |
Definition at line 151 of file gazebo_ros_pub_world_state.h.
std::string gazebo::GazeboRosPubWorldState::frameName [private] |
Definition at line 146 of file gazebo_ros_pub_world_state.h.
ParamT<std::string>* gazebo::GazeboRosPubWorldState::frameNameP [private] |
frame transform name, should match link name
Definition at line 145 of file gazebo_ros_pub_world_state.h.
boost::mutex gazebo::GazeboRosPubWorldState::lock [private] |
A mutex to lock access to fields that are used in message callbacks.
Definition at line 134 of file gazebo_ros_pub_world_state.h.
gazebo::Model* gazebo::GazeboRosPubWorldState::parent_model_ [private] |
: parent should be a model
Definition at line 127 of file gazebo_ros_pub_world_state.h.
ros::Publisher gazebo::GazeboRosPubWorldState::pub_ [private] |
Definition at line 131 of file gazebo_ros_pub_world_state.h.
ros::CallbackQueue gazebo::GazeboRosPubWorldState::queue_ [private] |
Definition at line 149 of file gazebo_ros_pub_world_state.h.
std::string gazebo::GazeboRosPubWorldState::robotNamespace [private] |
Definition at line 138 of file gazebo_ros_pub_world_state.h.
ParamT<std::string>* gazebo::GazeboRosPubWorldState::robotNamespaceP [private] |
for setting ROS name space
Definition at line 137 of file gazebo_ros_pub_world_state.h.
ros::NodeHandle* gazebo::GazeboRosPubWorldState::rosnode_ [private] |
: ros node handle and publisher
Definition at line 130 of file gazebo_ros_pub_world_state.h.
std::string gazebo::GazeboRosPubWorldState::topicName [private] |
Definition at line 142 of file gazebo_ros_pub_world_state.h.
ParamT<std::string>* gazebo::GazeboRosPubWorldState::topicNameP [private] |
topic name
Definition at line 141 of file gazebo_ros_pub_world_state.h.
int gazebo::GazeboRosPubWorldState::worldStateConnectCount [private] |
: keep track of number of connections
Definition at line 119 of file gazebo_ros_pub_world_state.h.
: Message for sending world state
Definition at line 124 of file gazebo_ros_pub_world_state.h.