#include <ROSInterface.h>
Public Member Functions | |
void | createPublisher (ros::NodeHandle &nh) |
void | publish () |
WorldToROSTF (osg::Group *rootNode, std::vector< boost::shared_ptr< SimulatedIAUV > > iauvFile, std::vector< osg::ref_ptr< osg::Node > > objects, std::string worldRootName, unsigned int enableObjects, int rate) | |
~WorldToROSTF () | |
Private Attributes | |
unsigned int | enableObjects_ |
std::vector< boost::shared_ptr < SimulatedIAUV > > | iauvFile_ |
std::vector< osg::ref_ptr < osg::Node > > | objects_ |
std::vector< boost::shared_ptr < robot_state_publisher::RobotStatePublisher > > | robot_pubs_ |
osg::Group * | rootNode_ |
boost::shared_ptr < tf::TransformBroadcaster > | tfpub_ |
std::vector< osg::ref_ptr < osg::MatrixTransform > > | transforms_ |
std::string | worldRootName_ |
Definition at line 265 of file ROSInterface.h.
WorldToROSTF::WorldToROSTF | ( | osg::Group * | rootNode, |
std::vector< boost::shared_ptr< SimulatedIAUV > > | iauvFile, | ||
std::vector< osg::ref_ptr< osg::Node > > | objects, | ||
std::string | worldRootName, | ||
unsigned int | enableObjects, | ||
int | rate | ||
) |
Definition at line 897 of file ROSInterface.cpp.
Definition at line 1002 of file ROSInterface.cpp.
void WorldToROSTF::createPublisher | ( | ros::NodeHandle & | nh | ) | [virtual] |
Implements ROSPublisherInterface.
Definition at line 937 of file ROSInterface.cpp.
void WorldToROSTF::publish | ( | ) | [virtual] |
Implements ROSPublisherInterface.
Definition at line 942 of file ROSInterface.cpp.
unsigned int WorldToROSTF::enableObjects_ [private] |
Definition at line 273 of file ROSInterface.h.
std::vector< boost::shared_ptr<SimulatedIAUV> > WorldToROSTF::iauvFile_ [private] |
Definition at line 270 of file ROSInterface.h.
std::vector<osg::ref_ptr<osg::Node> > WorldToROSTF::objects_ [private] |
Definition at line 271 of file ROSInterface.h.
std::vector< boost::shared_ptr<robot_state_publisher::RobotStatePublisher> > WorldToROSTF::robot_pubs_ [private] |
Definition at line 268 of file ROSInterface.h.
osg::Group* WorldToROSTF::rootNode_ [private] |
Definition at line 274 of file ROSInterface.h.
boost::shared_ptr<tf::TransformBroadcaster> WorldToROSTF::tfpub_ [private] |
Definition at line 269 of file ROSInterface.h.
std::vector< osg::ref_ptr<osg::MatrixTransform> > WorldToROSTF::transforms_ [private] |
Definition at line 267 of file ROSInterface.h.
std::string WorldToROSTF::worldRootName_ [private] |
Definition at line 272 of file ROSInterface.h.