Program Listing for File UDPClient.h

Return to documentation for file (/tmp/ws/src/sick_safetyscanners_base/include/sick_safetyscanners_base/communication/UDPClient.h)

// this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-

// -- BEGIN LICENSE BLOCK ----------------------------------------------

// -- END LICENSE BLOCK ------------------------------------------------

//----------------------------------------------------------------------
//----------------------------------------------------------------------

#ifndef SICK_SAFETYSCANNERS_BASE_COMMUNICATION_ASYNCUDPCLIENT_H
#define SICK_SAFETYSCANNERS_BASE_COMMUNICATION_ASYNCUDPCLIENT_H

#include <iostream>

#include <boost/asio.hpp>

#include "sick_safetyscanners_base/Types.h"
#include "sick_safetyscanners_base/datastructure/PacketBuffer.h"

namespace sick {
namespace communication {

class UDPClient
{
public:
  UDPClient(boost::asio::io_service& io_service, sick::types::port_t server_port);

  UDPClient(boost::asio::io_service& io_service,
            sick::types::port_t server_port,
            boost::asio::ip::address_v4 host_ip,
            boost::asio::ip::address_v4 interface_ip);

  UDPClient()                 = delete;
  UDPClient(const UDPClient&) = delete;
  UDPClient& operator=(const UDPClient&) = delete;

  virtual ~UDPClient();

  template <typename Callable>
  void run(Callable&& callback)
  {
    m_packet_handler = callback;
    beginReceive();
  }

  void stop();

  sick::types::port_t getLocalPort() const;

  bool isConnected() const;

  bool isDataAvailable() const;

  sick::datastructure::PacketBuffer receive(sick::types::time_duration_t timeout);

private:
  boost::asio::io_service& m_io_service;
  boost::asio::ip::udp::endpoint m_remote_endpoint;
  boost::asio::ip::udp::socket m_socket;
  types::PacketHandler m_packet_handler;
  datastructure::PacketBuffer::ArrayBuffer m_recv_buffer;
  boost::asio::deadline_timer m_deadline;

  void checkDeadline();

  void handleReceive(boost::system::error_code ec, std::size_t bytes_recv);

  void beginReceive();

  static void handleReceiveDeadline(const boost::system::error_code& ec,
                                    std::size_t length,
                                    boost::system::error_code* out_ec,
                                    std::size_t* out_length)
  {
    *out_ec     = ec;
    *out_length = length;
  }
};

} // namespace communication
} // namespace sick

#endif // SICK_SAFETYSCANNERS_BASE_COMMUNICATION_ASYNCUDPCLIENT_H