RmpUdp.cpp
Go to the documentation of this file.
00001 /*
00002   COPYRIGHT (c) 2014 SEGWAY Inc.
00003 
00004   Software License Agreement:
00005 
00006   The software supplied herewith by Segway Inc. (the "Company") for its 
00007   RMP Robotic Platforms is intended and supplied to you, the Company's 
00008   customer, for use solely and exclusively with Segway products. The 
00009   software is owned by the Company and/or its supplier, and is protected 
00010   under applicable copyright laws.  All rights are reserved. Any use in 
00011   violation of the foregoing restrictions may subject the user to criminal
00012   sanctions under applicable laws, as well as to civil liability for the 
00013   breach of the terms and conditions of this license. The Company may 
00014   immediately terminate this Agreement upon your use of the software with 
00015   any products that are not Segway products.
00016 
00017   You shall indemnify, defend and hold the Company harmless from any claims, 
00018   demands, liabilities or expenses, including reasonable attorneys fees, incurred 
00019   by the Company as a result of any claim or proceeding against the Company 
00020   arising out of or based upon: 
00021 
00022   (i) The combination, operation or use of the software by you with any hardware, 
00023       products, programs or data not supplied or approved in writing by the Company, 
00024       if such claim or proceeding would have been avoided but for such combination, 
00025       operation or use.
00026 
00027   (ii) The modification of the software by or on behalf of you.
00028 
00029   (iii) Your use of the software.
00030 
00031   THIS SOFTWARE IS PROVIDED IN AN "AS IS" CONDITION. NO WARRANTIES,
00032   WHETHER EXPRESS, IMPLIED, OR STATUTORY, INCLUDING, BUT NOT LIMITED
00033   TO, IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
00034   PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. THE COMPANY SHALL NOT,
00035   IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL OR
00036   CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
00037 */
00038 
00039 #include <RmpUdp.h>
00040 
00041 #include <memory>
00042 #include <utility>
00043 #include <iostream>
00044 #include <exception>
00045 
00046 #include <boost/asio.hpp>
00047 #include <boost/asio/deadline_timer.hpp>
00048 #include <boost/bind.hpp>
00049 #include <boost/date_time/posix_time/posix_time_types.hpp>
00050 
00051 #include <RmpHelper.h>
00052 #include <RmpLogger.h>
00053 
00054 namespace segway
00055 {
00056   using boost::asio::ip::udp;
00057 
00058   static const size_t MAX_RCV_SIZE = 1024;
00059   static const long TIMEOUT = 30; // [ms]
00060   
00061   class RmpUdp::Impl
00062   {
00063   public: 
00064     Impl(const udp::endpoint& rEndpoint);
00065     size_t Send(const Bytes& rData, float timeout, boost::system::error_code& rErrorCode);
00066     size_t Receive(Bytes& rData, float timeout, boost::system::error_code& rErrorCode);
00067 
00068   private:
00069     void CheckDeadline();
00070     static void Handle(const boost::system::error_code& rErrorCodeIn, size_t sizeIn, boost::system::error_code* pErrorCodeOut, std::size_t* pSizeOut);
00071     
00072     boost::asio::io_service m_IoService;
00073     udp::socket m_Socket;
00074     boost::asio::deadline_timer m_Timer;
00075     Bytes m_ReadBuffer;
00076   };
00077 
00078   RmpUdp::RmpUdp(const std::string& rIpAddress, uint16_t portNumber)
00079   {
00080     udp::endpoint endpoint(boost::asio::ip::address::from_string(rIpAddress.c_str()), portNumber);
00081 
00082     m_pImpl = std::unique_ptr<Impl>(new Impl(endpoint));
00083   }
00084 
00085   RmpUdp::~RmpUdp()
00086   {}
00087 
00088   bool RmpUdp::Send(uint16_t commandId, uint32_t value1, uint32_t value2)
00089   {
00090     Bytes message;
00091     ConvertCommandToBytes(commandId, value1, value2, message);
00092     AppendCrc16(message);
00093 
00094     boost::system::error_code errorCode;
00095     size_t bytesSent = m_pImpl->Send(message, TIMEOUT, errorCode);
00096 
00097     if (errorCode.value() != boost::system::errc::success)
00098     {
00099       SEGWAY_LOG(ERROR, "Fail to udp send: " << errorCode.message());
00100 
00101       return false;
00102     }
00103     
00104     if (bytesSent != message.size())
00105     {
00106       return false;
00107     }
00108 
00109     return true;
00110   }
00111   
00112   bool RmpUdp::Receive(Bytes& rData, size_t size)
00113   {
00114     rData.resize(size + CRC_FEEDBACK_SIZE);
00115 
00116     boost::system::error_code errorCode;
00117     size_t bytesReceived = m_pImpl->Receive(rData, TIMEOUT, errorCode);
00118 
00119     if (errorCode.value() != boost::system::errc::success)
00120     {
00121       SEGWAY_LOG(DEBUG, "Fail to receive udp packet: " << errorCode.message());
00122 
00123       return false;
00124     }
00125     
00126     if (bytesReceived != (size + CRC_FEEDBACK_SIZE))
00127     {
00128       SEGWAY_LOG(DEBUG, "Received udp packet of unexpected size: " << bytesReceived << ", expected: " << size + CRC_FEEDBACK_SIZE);
00129       
00130       return false;
00131     }
00132 
00133     if (!IsCrcValid(rData, bytesReceived))
00134     {
00135       SEGWAY_LOG(ERROR, "CRC mismatched on udp receive.");
00136 
00137       return false;
00138     }
00139 
00140     rData.erase(rData.begin() + size, rData.end());
00141 
00142     return true;
00143   }
00144 
00145   RmpUdp::Impl::Impl(const udp::endpoint& rEndpoint)
00146     : m_Socket(m_IoService)
00147     , m_Timer(m_IoService)
00148   {
00149     boost::system::error_code errorCode;
00150     m_Socket.connect(rEndpoint, errorCode);
00151 
00152     if (errorCode.value() != boost::system::errc::success)
00153     {
00154       std::stringstream stringStream;
00155       stringStream << "Unable to connect to socket: " << errorCode.message();
00156       
00157       throw std::runtime_error(stringStream.str());
00158     }
00159 
00160     m_ReadBuffer.resize(MAX_RCV_SIZE);
00161 
00162     m_Timer.expires_at(boost::posix_time::pos_infin);
00163          
00164     CheckDeadline();
00165   }
00166 
00167   size_t RmpUdp::Impl::Send(const Bytes& rData, float timeout, boost::system::error_code& rErrorCode)
00168   {
00169     m_Timer.expires_from_now(boost::posix_time::milliseconds(timeout));
00170 
00171     rErrorCode = boost::asio::error::would_block;
00172     size_t size = 0;
00173 
00174     m_Socket.async_send(boost::asio::buffer(rData), boost::bind(&Impl::Handle, _1, _2, &rErrorCode, &size));
00175 
00176     do
00177     {
00178       m_IoService.run_one();
00179     }
00180     while (rErrorCode == boost::asio::error::would_block);
00181     
00182     return size;
00183   }
00184 
00185   size_t RmpUdp::Impl::Receive(Bytes& rData, float timeout, boost::system::error_code& rErrorCode)
00186   {
00187     m_Timer.expires_from_now(boost::posix_time::milliseconds(timeout));
00188 
00189     rErrorCode = boost::asio::error::would_block;
00190     size_t size = 0;
00191 
00192     m_Socket.async_receive(boost::asio::buffer(m_ReadBuffer), boost::bind(&Impl::Handle, _1, _2, &rErrorCode, &size));
00193 
00194     do
00195     {
00196       m_IoService.run_one();
00197     }
00198     while (rErrorCode == boost::asio::error::would_block);
00199 
00200     if (size >= rData.size())
00201     {
00202       size_t startIdx = size - rData.size();
00203       rData.assign(m_ReadBuffer.begin() + startIdx, m_ReadBuffer.end() - 1);
00204     }
00205     else
00206     {
00207       rData.assign(m_ReadBuffer.begin(), m_ReadBuffer.end() - 1);
00208     }
00209     
00210     return size;
00211   }
00212 
00213   void RmpUdp::Impl::CheckDeadline()
00214   {
00215     if (m_Timer.expires_at() <= boost::asio::deadline_timer::traits_type::now())
00216     {
00217       m_Socket.cancel();
00218 
00219       m_Timer.expires_at(boost::posix_time::pos_infin);
00220     }
00221 
00222     m_Timer.async_wait(boost::bind(&Impl::CheckDeadline, this));
00223   }
00224 
00225   void RmpUdp::Impl::Handle(const boost::system::error_code& rErrorCodeIn, size_t sizeIn, boost::system::error_code* pErrorCodeOut, std::size_t* pSizeOut)
00226   {
00227     *pErrorCodeOut = rErrorCodeIn;
00228     *pSizeOut = sizeIn;
00229   }
00230   
00231 } // namespace segway


rmp_base
Author(s):
autogenerated on Wed Aug 26 2015 16:24:39