Program Listing for File trajectory_point_interface.h

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

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

// -- BEGIN LICENSE BLOCK ----------------------------------------------
// Copyright 2021 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_TRAJECTORY_INTERFACE_H_INCLUDED
#define UR_CLIENT_LIBRARY_TRAJECTORY_INTERFACE_H_INCLUDED

#include "ur_client_library/control/reverse_interface.h"
#include "ur_client_library/comm/control_mode.h"
#include "ur_client_library/types.h"
#include "ur_client_library/log.h"

namespace urcl
{
namespace control
{
enum class TrajectoryResult : int32_t
{

  TRAJECTORY_RESULT_SUCCESS = 0,
  TRAJECTORY_RESULT_CANCELED = 1,
  TRAJECTORY_RESULT_FAILURE = 2
};

enum class TrajectorySplineType : int32_t
{
  SPLINE_CUBIC = 1,
  SPLINE_QUINTIC = 2
};

enum class TrajectoryMotionType : int32_t
{
  JOINT_POINT = 0,
  CARTESIAN_POINT = 1,
  JOINT_POINT_SPLINE = 2
};

class TrajectoryPointInterface : public ReverseInterface
{
public:
  static const int32_t MULT_TIME = 1000;

  TrajectoryPointInterface() = delete;
  TrajectoryPointInterface(uint32_t port);

  virtual ~TrajectoryPointInterface() = default;

  bool writeTrajectoryPoint(const vector6d_t* positions, const float goal_time, const float blend_radius,
                            const bool cartesian);

  bool writeTrajectorySplinePoint(const vector6d_t* positions, const vector6d_t* velocities,
                                  const vector6d_t* accelerations, const float goal_time);

  void setTrajectoryEndCallback(std::function<void(TrajectoryResult)> callback)
  {
    handle_trajectory_end_ = callback;
  }

protected:
  virtual void connectionCallback(const int filedescriptor) override;

  virtual void disconnectionCallback(const int filedescriptor) override;

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

private:
  static const int MESSAGE_LENGTH = 21;
  std::function<void(TrajectoryResult)> handle_trajectory_end_;
};

}  // namespace control
}  // namespace urcl

#endif  // UR_CLIENT_LIBRARY_TRAJECTORY_INTERFACE_H_INCLUDED