Program Listing for File rtde_client.h

Return to documentation for file (/tmp/ws/src/ur_client_library/include/ur_client_library/rtde/rtde_client.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_RTDE_CLIENT_H_INCLUDED
#define UR_CLIENT_LIBRARY_RTDE_CLIENT_H_INCLUDED

#include "ur_client_library/comm/pipeline.h"
#include "ur_client_library/rtde/package_header.h"
#include "ur_client_library/rtde/rtde_package.h"
#include "ur_client_library/comm/stream.h"
#include "ur_client_library/rtde/rtde_parser.h"
#include "ur_client_library/comm/producer.h"
#include "ur_client_library/rtde/data_package.h"
#include "ur_client_library/rtde/request_protocol_version.h"
#include "ur_client_library/rtde/control_package_setup_outputs.h"
#include "ur_client_library/rtde/control_package_start.h"
#include "ur_client_library/log.h"
#include "ur_client_library/rtde/rtde_writer.h"

static const int UR_RTDE_PORT = 30004;
static const std::string PIPELINE_NAME = "RTDE Data Pipeline";

namespace urcl
{
namespace rtde_interface
{
static const uint16_t MAX_RTDE_PROTOCOL_VERSION = 2;
static const unsigned MAX_REQUEST_RETRIES = 5;
static const unsigned MAX_INITIALIZE_ATTEMPTS = 10;

enum class UrRtdeRobotStatusBits
{
  IS_POWER_ON = 0,
  IS_PROGRAM_RUNNING = 1,
  IS_TEACH_BUTTON_PRESSED = 2,
  IS_POWER_BUTTON_PRESSED = 3
};

enum class UrRtdeSafetyStatusBits
{
  IS_NORMAL_MODE = 0,
  IS_REDUCED_MODE = 1,
  IS_PROTECTIVE_STOPPED = 2,
  IS_RECOVERY_MODE = 3,
  IS_SAFEGUARD_STOPPED = 4,
  IS_SYSTEM_EMERGENCY_STOPPED = 5,
  IS_ROBOT_EMERGENCY_STOPPED = 6,
  IS_EMERGENCY_STOPPED = 7,
  IS_VIOLATION = 8,
  IS_FAULT = 9,
  IS_STOPPED_DUE_TO_SAFETY = 10
};

enum class ClientState
{
  UNINITIALIZED = 0,
  INITIALIZING = 1,
  INITIALIZED = 2,
  RUNNING = 3,
  PAUSED = 4
};

class RTDEClient
{
public:
  RTDEClient() = delete;
  RTDEClient(std::string robot_ip, comm::INotifier& notifier, const std::string& output_recipe_file,
             const std::string& input_recipe_file, double target_frequency = 0.0);

  RTDEClient(std::string robot_ip, comm::INotifier& notifier, const std::vector<std::string>& output_recipe,
             const std::vector<std::string>& input_recipe, double target_frequency = 0.0);
  ~RTDEClient();
  bool init(const size_t max_num_tries = 0,
            const std::chrono::milliseconds reconnection_time = std::chrono::seconds(10));
  bool start();
  bool pause();
  std::unique_ptr<rtde_interface::DataPackage> getDataPackage(std::chrono::milliseconds timeout);

  double getMaxFrequency() const
  {
    return max_frequency_;
  }

  double getTargetFrequency() const
  {
    return target_frequency_;
  }

  VersionInformation getVersion()
  {
    return urcontrol_version_;
  }

  std::string getIP() const;

  RTDEWriter& getWriter();

  std::vector<std::string> getOutputRecipe()
  {
    return output_recipe_;
  }

private:
  comm::URStream<RTDEPackage> stream_;
  std::vector<std::string> output_recipe_;
  std::vector<std::string> input_recipe_;
  RTDEParser parser_;
  comm::URProducer<RTDEPackage> prod_;
  comm::Pipeline<RTDEPackage> pipeline_;
  RTDEWriter writer_;

  VersionInformation urcontrol_version_;

  double max_frequency_;
  double target_frequency_;

  ClientState client_state_;

  constexpr static const double CB3_MAX_FREQUENCY = 125.0;
  constexpr static const double URE_MAX_FREQUENCY = 500.0;

  // Reads output or input recipe from a file
  std::vector<std::string> readRecipe(const std::string& recipe_file) const;

  // Helper function to ensure that timestamp is present in the output recipe. The timestamp is needed to ensure that
  // the robot is booted.
  std::vector<std::string> ensureTimestampIsPresent(const std::vector<std::string>& output_recipe) const;

  void setupCommunication(const size_t max_num_tries = 0,
                          const std::chrono::milliseconds reconnection_time = std::chrono::seconds(10));
  bool negotiateProtocolVersion(const uint16_t protocol_version);
  void queryURControlVersion();
  void setupOutputs(const uint16_t protocol_version);
  void setupInputs();
  void disconnect();

  bool isRobotBooted();
  bool sendStart();
  bool sendPause();

  std::vector<std::string> splitVariableTypes(const std::string& variable_types) const;
};

}  // namespace rtde_interface
}  // namespace urcl

#endif  // UR_CLIENT_LIBRARY_RTDE_CLIENT_H_INCLUDED