Classes | Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes
ROSSensorPublisher Class Reference

#include <rossensorpublisher.h>

List of all members.

Classes

class  EnvironmentSensorPublisher
class  RobotPublisher
class  SensorPublisher

Public Member Functions

virtual void Destroy ()
virtual int main (const std::string &args)
virtual void Reset ()
 ROSSensorPublisher (EnvironmentBasePtr penv)
virtual bool SimulationStep (dReal fElapsedTime)
virtual ~ROSSensorPublisher ()

Protected Member Functions

virtual void _threadrosfn ()
bool RegisterRobot (ostream &sout, istream &sinput)
bool RegisterSensor (ostream &sout, istream &sinput)
boost::shared_ptr
< ROSSensorPublisher
shared_problem ()
boost::shared_ptr
< ROSSensorPublisher const > 
shared_problem_const () const
bool UnregisterRobot (ostream &sout, istream &sinput)
bool UnregisterSensor (ostream &sout, istream &sinput)

Static Protected Member Functions

static geometry_msgs::Pose rosPose (const Transform &t)
static geometry_msgs::Vector3 rosVector3 (const Vector &v)

Protected Attributes

bool _bDestroyThread
boost::mutex _mutex
map< RobotBasePtr,
boost::shared_ptr
< RobotPublisher > > 
_robots
boost::shared_ptr
< ros::NodeHandle
_ros
map< SensorBasePtr,
boost::shared_ptr
< EnvironmentSensorPublisher > > 
_sensors
boost::thread _threadros

Detailed Description

Definition at line 32 of file rossensorpublisher.h.


Constructor & Destructor Documentation

ROSSensorPublisher::ROSSensorPublisher ( EnvironmentBasePtr  penv) [inline]

Definition at line 35 of file rossensorpublisher.h.

virtual ROSSensorPublisher::~ROSSensorPublisher ( ) [inline, virtual]

Definition at line 46 of file rossensorpublisher.h.


Member Function Documentation

virtual void ROSSensorPublisher::_threadrosfn ( ) [inline, protected, virtual]

Definition at line 100 of file rossensorpublisher.h.

virtual void ROSSensorPublisher::Destroy ( ) [inline, virtual]

Definition at line 50 of file rossensorpublisher.h.

virtual int ROSSensorPublisher::main ( const std::string args) [inline, virtual]

Definition at line 71 of file rossensorpublisher.h.

bool ROSSensorPublisher::RegisterRobot ( ostream &  sout,
istream &  sinput 
) [inline, protected]

Definition at line 599 of file rossensorpublisher.h.

bool ROSSensorPublisher::RegisterSensor ( ostream &  sout,
istream &  sinput 
) [inline, protected]

Definition at line 697 of file rossensorpublisher.h.

virtual void ROSSensorPublisher::Reset ( ) [inline, virtual]

Definition at line 61 of file rossensorpublisher.h.

static geometry_msgs::Pose ROSSensorPublisher::rosPose ( const Transform &  t) [inline, static, protected]

Definition at line 108 of file rossensorpublisher.h.

static geometry_msgs::Vector3 ROSSensorPublisher::rosVector3 ( const Vector v) [inline, static, protected]

Definition at line 121 of file rossensorpublisher.h.

boost::shared_ptr<ROSSensorPublisher> ROSSensorPublisher::shared_problem ( ) [inline, protected]

Definition at line 93 of file rossensorpublisher.h.

boost::shared_ptr<ROSSensorPublisher const> ROSSensorPublisher::shared_problem_const ( ) const [inline, protected]

Definition at line 96 of file rossensorpublisher.h.

virtual bool ROSSensorPublisher::SimulationStep ( dReal  fElapsedTime) [inline, virtual]

Definition at line 87 of file rossensorpublisher.h.

bool ROSSensorPublisher::UnregisterRobot ( ostream &  sout,
istream &  sinput 
) [inline, protected]

Definition at line 640 of file rossensorpublisher.h.

bool ROSSensorPublisher::UnregisterSensor ( ostream &  sout,
istream &  sinput 
) [inline, protected]

Definition at line 738 of file rossensorpublisher.h.


Member Data Documentation

Definition at line 772 of file rossensorpublisher.h.

boost::mutex ROSSensorPublisher::_mutex [protected]

Definition at line 771 of file rossensorpublisher.h.

map<RobotBasePtr,boost::shared_ptr<RobotPublisher> > ROSSensorPublisher::_robots [protected]

Definition at line 768 of file rossensorpublisher.h.

boost::shared_ptr<ros::NodeHandle> ROSSensorPublisher::_ros [protected]

Definition at line 767 of file rossensorpublisher.h.

map<SensorBasePtr,boost::shared_ptr<EnvironmentSensorPublisher> > ROSSensorPublisher::_sensors [protected]

Definition at line 769 of file rossensorpublisher.h.

boost::thread ROSSensorPublisher::_threadros [protected]

Definition at line 770 of file rossensorpublisher.h.


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


openrave_sensors
Author(s): Rosen Diankov (rosen.diankov@gmail.com)
autogenerated on Sat Mar 23 2013 18:07:40