udp_server.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2014 Norwegian University of Science and Technology
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Norwegian University of Science and
00018  *     Technology, nor the names of its contributors may be used to
00019  *     endorse or promote products derived from this software without
00020  *     specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 /*
00037  * Author: Lars Tingelstad
00038  */
00039 
00040 #ifndef KUKA_RSI_HARDWARE_INTERFACE_UDP_SERVER_
00041 #define KUKA_RSI_HARDWARE_INTERFACE_UDP_SERVER_
00042 
00043 #include <iostream>
00044 #include <string>
00045 #include <stdexcept>
00046 
00047 // Select includes
00048 #include <sys/time.h>
00049 
00050 #include <string.h>
00051 #include <stdio.h>
00052 #include <unistd.h>
00053 #include <stdlib.h>
00054 #include <netdb.h>
00055 #include <sys/types.h>
00056 #include <sys/socket.h>
00057 #include <netinet/in.h>
00058 #include <arpa/inet.h>
00059 
00060 #define BUFSIZE 1024
00061 
00062 class UDPServer
00063 {
00064 public:
00065   UDPServer(std::string host, unsigned short port) : local_host_(host), local_port_(port), timeout_(false)
00066   {
00067     sockfd_ = socket(AF_INET, SOCK_DGRAM, 0);
00068     if (sockfd_ < 0)
00069       throw std::runtime_error("Error opening socket: " + std::string(strerror(errno)));
00070     optval = 1;
00071     setsockopt(sockfd_, SOL_SOCKET, SO_REUSEADDR, (const void *)&optval , sizeof(int));
00072     memset(&serveraddr_, 0, sizeof(serveraddr_));
00073     serveraddr_.sin_family = AF_INET;
00074     serveraddr_.sin_addr.s_addr = inet_addr(local_host_.c_str());
00075     serveraddr_.sin_port = htons(local_port_);
00076     if (bind(sockfd_, (struct sockaddr *) &serveraddr_, sizeof(serveraddr_)) < 0)
00077       throw std::runtime_error("Error binding socket: " + std::string(strerror(errno)));
00078     clientlen_ = sizeof(clientaddr_);
00079   }
00080 
00081   ~UDPServer()
00082   {
00083     close(sockfd_);
00084   }
00085 
00086   bool set_timeout(int millisecs)
00087   {
00088     if (millisecs != 0)
00089     {
00090       tv_.tv_sec  = millisecs / 1000;
00091       tv_.tv_usec = (millisecs % 1000) * 1000;
00092       timeout_ = true;
00093       return timeout_;
00094     }
00095     else
00096     {
00097       return timeout_;
00098     }
00099   }
00100 
00101   ssize_t send(std::string& buffer)
00102   {
00103     ssize_t bytes = 0;
00104     bytes = sendto(sockfd_, buffer.c_str(), buffer.size(), 0, (struct sockaddr *) &clientaddr_, clientlen_);
00105     if (bytes < 0)
00106     {
00107       std::cout << "ERROR in sendto" << std::endl;
00108     }
00109 
00110     return bytes;
00111   }
00112 
00113   ssize_t recv(std::string& buffer)
00114   {
00115     ssize_t bytes = 0;
00116 
00117     if (timeout_)
00118     {
00119       fd_set read_fds;
00120       FD_ZERO(&read_fds);
00121       FD_SET(sockfd_, &read_fds);
00122 
00123       struct timeval tv;
00124       tv.tv_sec = tv_.tv_sec;
00125       tv.tv_usec = tv_.tv_usec;
00126 
00127       if (select(sockfd_+1, &read_fds, NULL, NULL, &tv) < 0)
00128       {
00129         return 0;
00130       }
00131 
00132       if (FD_ISSET(sockfd_, &read_fds))
00133       {
00134         memset(buffer_, 0, BUFSIZE);
00135         bytes = recvfrom(sockfd_, buffer_, BUFSIZE, 0, (struct sockaddr *) &clientaddr_, &clientlen_);
00136         if (bytes < 0)
00137         {
00138           std::cout << "ERROR in recvfrom" << std::endl;
00139         }
00140       }
00141       else
00142       {
00143         return 0;
00144       }
00145 
00146     }
00147     else
00148     {
00149       memset(buffer_, 0, BUFSIZE);
00150       bytes = recvfrom(sockfd_, buffer_, BUFSIZE, 0, (struct sockaddr *) &clientaddr_, &clientlen_);
00151       if (bytes < 0)
00152       {
00153         std::cout << "ERROR in recvfrom" << std::endl;
00154       }
00155     }
00156 
00157     buffer = std::string(buffer_);
00158 
00159     return bytes;
00160   }
00161 
00162 private:
00163   std::string local_host_;
00164   unsigned short local_port_;
00165   bool timeout_;
00166   struct timeval tv_;
00167 
00168   int sockfd_;
00169   socklen_t clientlen_;
00170   struct sockaddr_in serveraddr_;
00171   struct sockaddr_in clientaddr_;
00172   char buffer_[BUFSIZE];
00173   int optval;
00174 
00175 };
00176 
00177 #endif
00178 


kuka_rsi_hw_interface
Author(s): Lars Tingelstad
autogenerated on Thu Jun 6 2019 17:56:48