CameraTcpServer.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2011-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 #include "find_object/Settings.h"
00028 #include "find_object/utilite/ULogger.h"
00029 
00030 #include "CameraTcpServer.h"
00031 #include <QtNetwork/QTcpSocket>
00032 #include <QtNetwork/QNetworkInterface>
00033 #include <QtCore/QDataStream>
00034 
00035 namespace find_object {
00036 
00037 CameraTcpServer::CameraTcpServer(quint16 port, QObject *parent) :
00038         QTcpServer(parent),
00039     blockSize_(0)
00040 {
00041         if (!this->listen(QHostAddress::Any, port))
00042         {
00043                 UERROR("Unable to start the Camera TCP server: %s", this->errorString().toStdString().c_str());
00044                 return;
00045         }
00046 }
00047 
00048 cv::Mat CameraTcpServer::getImage()
00049 {
00050         cv::Mat img;
00051         if(images_.size())
00052         {
00053                 // if queue changed after tcp connection ended with images still in the buffer
00054                 int queue = Settings::getCamera_9queueSize();
00055                 while(queue > 0 && images_.size() > queue)
00056                 {
00057                         images_.pop_front();
00058                 }
00059 
00060                 img = images_.front();
00061                 images_.pop_front();
00062         }
00063         if(this->findChildren<QTcpSocket*>().size() == 1)
00064         {
00065                 this->findChildren<QTcpSocket*>().first()->waitForReadyRead(100);
00066         }
00067         return img;
00068 }
00069 
00070 bool CameraTcpServer::isConnected() const
00071 {
00072         return this->findChildren<QTcpSocket*>().size() > 0;
00073 }
00074 
00075 QHostAddress CameraTcpServer::getHostAddress() const
00076 {
00077         QHostAddress hostAddress;
00078 
00079         QList<QHostAddress> ipAddressesList = QNetworkInterface::allAddresses();
00080         // use the first non-localhost IPv4 address
00081         for (int i = 0; i < ipAddressesList.size(); ++i)
00082         {
00083                 if (ipAddressesList.at(i) != QHostAddress::LocalHost && ipAddressesList.at(i).toIPv4Address())
00084                 {
00085                         hostAddress = ipAddressesList.at(i).toString();
00086                         break;
00087                 }
00088         }
00089 
00090         // if we did not find one, use IPv4 localhost
00091         if (hostAddress.isNull())
00092         {
00093                 hostAddress = QHostAddress(QHostAddress::LocalHost);
00094         }
00095 
00096         return hostAddress;
00097 }
00098 
00099 quint16 CameraTcpServer::getPort() const
00100 {
00101         return this->serverPort();
00102 }
00103 
00104 void CameraTcpServer::incomingConnection(int socketDescriptor)
00105 {
00106         QList<QTcpSocket*> clients = this->findChildren<QTcpSocket*>();
00107         if(clients.size() >= 1)
00108         {
00109                 UWARN("A client is already connected. Only one connection allowed at the same time.");
00110                 QTcpSocket socket;
00111                 socket.setSocketDescriptor(socketDescriptor);
00112                 socket.close(); // close without sending an acknowledge
00113         }
00114         else
00115         {
00116                 QTcpSocket * socket = new QTcpSocket(this);
00117                 connect(socket, SIGNAL(readyRead()), this, SLOT(readReceivedData()));
00118                 connect(socket, SIGNAL(error(QAbstractSocket::SocketError)), this, SLOT(displayError(QAbstractSocket::SocketError)));
00119                 connect(socket, SIGNAL(disconnected()), this, SLOT(connectionLost()));
00120                 socket->setSocketDescriptor(socketDescriptor);
00121                 socket->write(QByteArray("1")); // send acknowledge
00122         }
00123 }
00124 
00125 void CameraTcpServer::readReceivedData()
00126 {
00127         QTcpSocket * client = (QTcpSocket*)sender();
00128         QDataStream in(client);
00129         in.setVersion(QDataStream::Qt_4_0);
00130 
00131         if (blockSize_ == 0)
00132         {
00133                 if (client->bytesAvailable() < (int)sizeof(quint64))
00134                 {
00135                         return;
00136                 }
00137 
00138                 in >> blockSize_;
00139         }
00140 
00141         if (client->bytesAvailable() < (int)blockSize_)
00142         {
00143                 return;
00144         }
00145 
00146         std::vector<unsigned char> buf(blockSize_);
00147         in.readRawData((char*)buf.data(), blockSize_);
00148         images_.push_back(cv::imdecode(buf, cv::IMREAD_UNCHANGED));
00149         int queue = Settings::getCamera_9queueSize();
00150         while(queue > 0 && images_.size() > queue)
00151         {
00152                 images_.pop_front();
00153         }
00154         blockSize_ = 0;
00155 }
00156 
00157 void CameraTcpServer::displayError(QAbstractSocket::SocketError socketError)
00158 {
00159         switch (socketError)
00160         {
00161                 case QAbstractSocket::RemoteHostClosedError:
00162                         break;
00163                 case QAbstractSocket::HostNotFoundError:
00164                         UWARN("CameraTcp: Tcp error: The host was not found. Please "
00165                                         "check the host name and port settings.\n");
00166                         break;
00167                 case QAbstractSocket::ConnectionRefusedError:
00168                         UWARN("CameraTcp: The connection was refused by the peer. "
00169                                         "Make sure your images server is running, "
00170                                         "and check that the host name and port "
00171                                         "settings are correct.");
00172                         break;
00173                 default:
00174                         //UERROR("The following error occurred: %s.", this->errorString().toStdString().c_str());
00175                         break;
00176         }
00177 }
00178 
00179 void CameraTcpServer::connectionLost()
00180 {
00181         //printf("[WARNING] CameraTcp: Connection lost!\n");
00182         ((QTcpSocket*)sender())->close();
00183         sender()->deleteLater();
00184         blockSize_ = 0; // reset
00185 }
00186 
00187 } // namespace find_object


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Thu Feb 11 2016 22:57:56