Program Listing for File reverse_interface.h

Return to documentation for file (/tmp/ws/src/ur_client_library/include/ur_client_library/control/reverse_interface.h)

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

// -- BEGIN LICENSE BLOCK ----------------------------------------------
// Copyright 2019 FZI Forschungszentrum Informatik
// Created on behalf of Universal Robots A/S
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
// -- END LICENSE BLOCK ------------------------------------------------

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

#ifndef UR_CLIENT_LIBRARY_REVERSE_INTERFACE_H_INCLUDED
#define UR_CLIENT_LIBRARY_REVERSE_INTERFACE_H_INCLUDED

#include "ur_client_library/comm/tcp_server.h"
#include "ur_client_library/comm/control_mode.h"
#include "ur_client_library/types.h"
#include "ur_client_library/log.h"
#include "ur_client_library/ur/robot_receive_timeout.h"
#include <cstring>
#include <endian.h>
#include <condition_variable>

namespace urcl
{
namespace control
{
enum class TrajectoryControlMessage : int32_t
{
  TRAJECTORY_CANCEL = -1,
  TRAJECTORY_NOOP = 0,
  TRAJECTORY_START = 1,
};

enum class FreedriveControlMessage : int32_t
{
  FREEDRIVE_STOP = -1,
  FREEDRIVE_NOOP = 0,
  FREEDRIVE_START = 1,
};

class ReverseInterface
{
public:
  static const int32_t MULT_JOINTSTATE = 1000000;

  ReverseInterface() = delete;
  ReverseInterface(uint32_t port, std::function<void(bool)> handle_program_state,
                   std::chrono::milliseconds step_time = std::chrono::milliseconds(8));

  virtual ~ReverseInterface() = default;

  virtual bool write(const vector6d_t* positions, const comm::ControlMode control_mode = comm::ControlMode::MODE_IDLE,
                     const RobotReceiveTimeout& robot_receive_timeout = RobotReceiveTimeout::millisec(20));

  bool
  writeTrajectoryControlMessage(const TrajectoryControlMessage trajectory_action, const int point_number = 0,
                                const RobotReceiveTimeout& robot_receive_timeout = RobotReceiveTimeout::millisec(200));

  bool
  writeFreedriveControlMessage(const FreedriveControlMessage freedrive_action,
                               const RobotReceiveTimeout& robot_receive_timeout = RobotReceiveTimeout::millisec(200));

  [[deprecated("Set keepaliveCount is deprecated, instead use the robot receive timeout directly in the write "
               "commands.")]] virtual void
  setKeepaliveCount(const uint32_t count);

protected:
  virtual void connectionCallback(const int filedescriptor);

  virtual void disconnectionCallback(const int filedescriptor);

  virtual void messageCallback(const int filedescriptor, char* buffer, int nbytesrecv);

  int client_fd_;
  comm::TCPServer server_;

  template <typename T>
  size_t append(uint8_t* buffer, T& val)
  {
    size_t s = sizeof(T);
    std::memcpy(buffer, &val, s);
    return s;
  }

  static const int MAX_MESSAGE_LENGTH = 8;

  std::function<void(bool)> handle_program_state_;
  std::chrono::milliseconds step_time_;

  uint32_t keepalive_count_;
  bool keep_alive_count_modified_deprecated_;
};

}  // namespace control
}  // namespace urcl

#endif  // UR_CLIENT_LIBRARY_REVERSE_INTERFACE_H_INCLUDED