VrMagicHandler_roshost.cpp
Go to the documentation of this file.
00001 /*
00002  * VrMagicHandlerroshost.cpp
00003  *
00004  *  Created on: 29.07.2014
00005  *      Author: m1ch1
00006  */
00007 
00008 #include "VrMagicHandler_roshost.h"
00009 
00010 namespace ohm
00011 {
00012 
00013 ohm::VrMagicHandler_roshost::VrMagicHandler_roshost(std::string ip_smartcam,
00014         unsigned int port_smartcam)
00015 {
00016     _ip = ip_smartcam;
00017     _port = port_smartcam;
00018 
00019     _tcpClient = new apps::TCP(_ip, _port);
00020 
00021     _imgHeader = new OHM_HEADER_TYPE[ohm::HEADER_SIZE];
00022     _imgData = NULL;
00023     _currentDataSize = 0;
00024 }
00025 
00026 ohm::VrMagicHandler_roshost::~VrMagicHandler_roshost()
00027 {
00028     delete _tcpClient;
00029     delete _imgHeader;
00030     if(_imgData != NULL)    delete _imgData;
00031 }
00032 
00033 void ohm::VrMagicHandler_roshost::connect()
00034 {
00035     //wait for connection to smartcam
00036     _tcpClient->connectOnce();
00037 }
00038 
00039 int ohm::VrMagicHandler_roshost::readImage(ImageType& image)
00040 {
00041     //read Header
00042     if(_tcpClient->readAll(_imgHeader, (unsigned int)ohm::HEADER_SIZE * sizeof(OHM_HEADER_TYPE)) != 0)
00043     {
00044         return -1;
00045     }
00046     unsigned int dataSize = _imgHeader[ohm::DATA_SIZE];
00047 
00048     //prove and allocate databuffer if needed
00049     if(dataSize > _currentDataSize)
00050     {//allocate new dataSize;
00051         if(_imgData != NULL)
00052             delete _imgData;
00053         //todo: if compressed data allocate more buffer for safety
00054         _imgData = new OHM_DATA_TYPE[dataSize];
00055     }
00056 
00057     //read image data
00058     if(_tcpClient->readAll(_imgData, dataSize) != 0)
00059     {
00060         return -1;
00061     }
00062 
00063     //set data in ImageType image
00064     image.id                = _imgHeader[ohm::ID];
00065     image.dataSize          = _imgHeader[ohm::DATA_SIZE];
00066     image.dataType          = (ohm::Data)_imgHeader[ohm::DATA_TYPE];
00067     image.compressionType   = (ohm::Compression)_imgHeader[ohm::COMPRESSION_TYPE];
00068     image.width             = _imgHeader[ohm::WIDTH];
00069     image.height            = _imgHeader[ohm::HEIGHT];
00070     image.channels          = _imgHeader[ohm::CHANNELS];
00071     image.bytePerPixel      = _imgHeader[ohm::BYTE_PER_PIXEL];
00072     //just set pointer to data
00073     image.data = _imgData;
00074 
00075     return 0;
00076 }
00077 
00078 //int VrMagicHandler_roshost::triggerImage()
00079 //{
00080 //    OHM_TRIGGER_TYPE trigger = ohm::IMAGE_REQUEST;
00081 //    if(_tcpClient->write(&trigger,sizeof(OHM_TRIGGER_TYPE)) != 0)
00082 //    {
00083 //        return -1;
00084 //    }
00085 //    return 0;
00086 //}
00087 
00088 const std::string& ohm::VrMagicHandler_roshost::getIp() const
00089 {
00090     return _ip;
00091 }
00092 
00093 unsigned int ohm::VrMagicHandler_roshost::getPort() const
00094 {
00095     return _port;
00096 }
00097 
00098 } /* namespace ohm */
00099 
00100 


vrmagic_ros_bridge_server
Author(s): Michael Schmidpeter
autogenerated on Thu Aug 27 2015 15:40:39