#include <VrMagicRosBridge_host.h>
Public Member Functions | |
| void | start (const unsigned int rate=10) |
| VrMagicRosBridge_host () | |
| virtual | ~VrMagicRosBridge_host () |
Private Member Functions | |
| int | addPublisher (unsigned int id) |
| bool | provePublisherExist (unsigned int id) |
| int | removePublischer (unsigned int id) |
| void | run () |
| this function containts the main working loop | |
| void | setMsgImage (unsigned int id) |
Private Attributes | |
| ohm::ImageType | _imgSmarcam |
| unsigned int | _loopRate |
| std::map< unsigned int, sensor_msgs::Image * > | _msgImgs |
| ros::NodeHandle | _nh |
| std::map< unsigned int, ros::Publisher > | _publishers |
| std::string | _pubName_base |
| ros::Rate * | _rate |
| std::map< unsigned int, unsigned int > | _seq |
| ohm::VrMagicHandler_roshost * | _smartcamHandler |
Definition at line 15 of file VrMagicRosBridge_host.h.
Definition at line 4 of file VrMagicRosBridge_host.cpp.
| VrMagicRosBridge_host::~VrMagicRosBridge_host | ( | ) | [virtual] |
Definition at line 22 of file VrMagicRosBridge_host.cpp.
| int VrMagicRosBridge_host::addPublisher | ( | unsigned int | id | ) | [private] |
Definition at line 75 of file VrMagicRosBridge_host.cpp.
| bool VrMagicRosBridge_host::provePublisherExist | ( | unsigned int | id | ) | [private] |
Definition at line 106 of file VrMagicRosBridge_host.cpp.
| int VrMagicRosBridge_host::removePublischer | ( | unsigned int | id | ) | [private] |
Definition at line 100 of file VrMagicRosBridge_host.cpp.
| void VrMagicRosBridge_host::run | ( | ) | [private] |
this function containts the main working loop
| [in,out] | void |
Definition at line 37 of file VrMagicRosBridge_host.cpp.
| void VrMagicRosBridge_host::setMsgImage | ( | unsigned int | id | ) | [private] |
Definition at line 116 of file VrMagicRosBridge_host.cpp.
| void VrMagicRosBridge_host::start | ( | const unsigned int | frames = 10 | ) |
| [in] | const | unsigned int rate -> rate of the working loop in [1/s] |
Definition at line 29 of file VrMagicRosBridge_host.cpp.
Definition at line 60 of file VrMagicRosBridge_host.h.
unsigned int VrMagicRosBridge_host::_loopRate [private] |
Definition at line 57 of file VrMagicRosBridge_host.h.
std::map<unsigned int, sensor_msgs::Image*> VrMagicRosBridge_host::_msgImgs [private] |
Definition at line 68 of file VrMagicRosBridge_host.h.
ros::NodeHandle VrMagicRosBridge_host::_nh [private] |
Definition at line 65 of file VrMagicRosBridge_host.h.
std::map<unsigned int, ros::Publisher> VrMagicRosBridge_host::_publishers [private] |
Definition at line 67 of file VrMagicRosBridge_host.h.
std::string VrMagicRosBridge_host::_pubName_base [private] |
Definition at line 58 of file VrMagicRosBridge_host.h.
ros::Rate* VrMagicRosBridge_host::_rate [private] |
Definition at line 64 of file VrMagicRosBridge_host.h.
std::map<unsigned int, unsigned int> VrMagicRosBridge_host::_seq [private] |
Definition at line 69 of file VrMagicRosBridge_host.h.
Definition at line 62 of file VrMagicRosBridge_host.h.