Program Listing for File SVHReceiveThread.h

Return to documentation for file (/tmp/ws/src/schunk_svh_library/include/schunk_svh_library/serial/SVHReceiveThread.h)

//
// © Copyright 2022 SCHUNK Mobile Greifsysteme GmbH, Lauffen/Neckar Germany
// © Copyright 2022 FZI Forschungszentrum Informatik, Karlsruhe, Germany
//
// This file is part of the Schunk SVH Library.
//
// The Schunk SVH Library is free software: you can redistribute it and/or
// modify it under the terms of the GNU General Public License as published by
// the Free Software Foundation, either version 3 of the License, or (at your
// option) any later version.
//
// The Schunk SVH Library is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
// Public License for more details.
//
// You should have received a copy of the GNU General Public License along with
// the Schunk SVH Library. If not, see <https://www.gnu.org/licenses/>.
//

//----------------------------------------------------------------------
//----------------------------------------------------------------------
#ifndef DRIVER_SVH_SVH_RECEIVE_THREAD_H_INCLUDED
#define DRIVER_SVH_SVH_RECEIVE_THREAD_H_INCLUDED

#include <schunk_svh_library/serial/ByteOrderConversion.h>
#include <schunk_svh_library/serial/Serial.h>

#include <schunk_svh_library/serial/SVHSerialPacket.h>

#include <atomic>
#include <chrono>
#include <functional>
#include <memory>

using driver_svh::serial::Serial;

namespace driver_svh {

using ReceivedPacketCallback =
  std::function<void(const SVHSerialPacket& packet, unsigned int packet_count)>;

class SVHReceiveThread
{
public:
  SVHReceiveThread(const std::chrono::microseconds& idle_sleep,
                   std::shared_ptr<Serial> device,
                   ReceivedPacketCallback const& received_callback);

  ~SVHReceiveThread() {}

  void run();

  void stop() { m_continue = false; };

  unsigned int receivedPacketCount() { return m_packets_received; }

  void resetReceivedPackageCount() { m_packets_received = 0; }

private:
  std::atomic<bool> m_continue{true};

  std::chrono::microseconds m_idle_sleep;

  std::shared_ptr<Serial> m_serial_device;

  enum
  {
    RS_HEADE_R1,
    RS_HEADE_R2,
    RS_INDEX,
    RS_ADDRESS,
    RS_LENGT_H1,
    RS_LENGT_H2,
    RS_DATA,
    RS_CHECKSU_M1,
    RS_CHECKSU_M2
  } typedef tState;

  tState m_received_state;

  uint16_t m_length;

  uint8_t m_checksum1;
  uint8_t m_checksum2;

  std::vector<uint8_t> m_data;

  driver_svh::ArrayBuilder m_ab;

  std::atomic<unsigned int> m_packets_received;

  unsigned int m_skipped_bytes;

  bool receiveData();

  ReceivedPacketCallback m_received_callback;
};

} // namespace driver_svh

#endif