reverse_interface.h
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2 
3 // -- BEGIN LICENSE BLOCK ----------------------------------------------
4 // Copyright 2019 FZI Forschungszentrum Informatik
5 // Created on behalf of Universal Robots A/S
6 //
7 // Licensed under the Apache License, Version 2.0 (the "License");
8 // you may not use this file except in compliance with the License.
9 // You may obtain a copy of the License at
10 //
11 // http://www.apache.org/licenses/LICENSE-2.0
12 //
13 // Unless required by applicable law or agreed to in writing, software
14 // distributed under the License is distributed on an "AS IS" BASIS,
15 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
16 // See the License for the specific language governing permissions and
17 // limitations under the License.
18 // -- END LICENSE BLOCK ------------------------------------------------
19 
20 //----------------------------------------------------------------------
27 //----------------------------------------------------------------------
28 
29 #ifndef UR_CLIENT_LIBRARY_REVERSE_INTERFACE_H_INCLUDED
30 #define UR_CLIENT_LIBRARY_REVERSE_INTERFACE_H_INCLUDED
31 
35 #include "ur_client_library/log.h"
37 #include <cstring>
38 #include <endian.h>
39 #include <condition_variable>
40 
41 namespace urcl
42 {
43 namespace control
44 {
48 enum class TrajectoryControlMessage : int32_t
49 {
50  TRAJECTORY_CANCEL = -1,
51  TRAJECTORY_NOOP = 0,
52  TRAJECTORY_START = 1,
53 };
54 
58 enum class FreedriveControlMessage : int32_t
59 {
60  FREEDRIVE_STOP = -1,
61  FREEDRIVE_NOOP = 0,
62  FREEDRIVE_START = 1,
63 };
64 
70 {
71 public:
72  static const int32_t MULT_JOINTSTATE = 1000000;
73 
74  ReverseInterface() = delete;
82  ReverseInterface(uint32_t port, std::function<void(bool)> handle_program_state,
83  std::chrono::milliseconds step_time = std::chrono::milliseconds(8));
84 
88  virtual ~ReverseInterface() = default;
89 
103  virtual bool write(const vector6d_t* positions, const comm::ControlMode control_mode = comm::ControlMode::MODE_IDLE,
104  const RobotReceiveTimeout& robot_receive_timeout = RobotReceiveTimeout::millisec(20));
105 
117  bool
118  writeTrajectoryControlMessage(const TrajectoryControlMessage trajectory_action, const int point_number = 0,
119  const RobotReceiveTimeout& robot_receive_timeout = RobotReceiveTimeout::millisec(200));
120 
131  bool
133  const RobotReceiveTimeout& robot_receive_timeout = RobotReceiveTimeout::millisec(200));
134 
140  [[deprecated("Set keepaliveCount is deprecated, instead use the robot receive timeout directly in the write "
141  "commands.")]] virtual void
142  setKeepaliveCount(const uint32_t count);
143 
144  void registerDisconnectionCallback(std::function<void(const int)> disconnection_fun)
145  {
146  disconnection_callback_ = disconnection_fun;
147  }
148 
154  bool isConnected() const
155  {
156  return client_fd_ != INVALID_SOCKET;
157  }
158 
159 protected:
160  virtual void connectionCallback(const socket_t filedescriptor);
161 
162  virtual void disconnectionCallback(const socket_t filedescriptor);
163 
164  virtual void messageCallback(const socket_t filedescriptor, char* buffer, int nbytesrecv);
165 
166  std::function<void(const int)> disconnection_callback_ = nullptr;
169 
170  template <typename T>
171  size_t append(uint8_t* buffer, T& val)
172  {
173  size_t s = sizeof(T);
174  std::memcpy(buffer, &val, s);
175  return s;
176  }
177 
178  static const int MAX_MESSAGE_LENGTH = 8;
179 
180  std::function<void(bool)> handle_program_state_;
181  std::chrono::milliseconds step_time_;
182 
185 };
186 
187 } // namespace control
188 } // namespace urcl
189 
190 #endif // UR_CLIENT_LIBRARY_REVERSE_INTERFACE_H_INCLUDED
urcl::comm::ControlMode
ControlMode
Control modes as interpreted from the script runnning on the robot.
Definition: control_mode.h:42
socket_t
int socket_t
Definition: socket_t.h:57
robot_receive_timeout.h
urcl::control::ReverseInterface::disconnectionCallback
virtual void disconnectionCallback(const socket_t filedescriptor)
Definition: reverse_interface.cpp:230
types.h
urcl::control::ReverseInterface::disconnection_callback_
std::function< void(const int)> disconnection_callback_
Definition: reverse_interface.h:166
INVALID_SOCKET
#define INVALID_SOCKET
Definition: socket_t.h:60
urcl::control::ReverseInterface::setKeepaliveCount
virtual void setKeepaliveCount(const uint32_t count)
Set the Keepalive count. This will set the number of allowed timeout reads on the robot.
Definition: reverse_interface.cpp:205
urcl::control::ReverseInterface::append
size_t append(uint8_t *buffer, T &val)
Definition: reverse_interface.h:171
control_mode.h
urcl
Definition: bin_parser.h:36
urcl::control::ReverseInterface::MULT_JOINTSTATE
static const int32_t MULT_JOINTSTATE
Definition: reverse_interface.h:72
urcl::control::ReverseInterface
The ReverseInterface class handles communication to the robot. It starts a server and waits for the r...
Definition: reverse_interface.h:69
urcl::control::ReverseInterface::write
virtual bool write(const vector6d_t *positions, const comm::ControlMode control_mode=comm::ControlMode::MODE_IDLE, const RobotReceiveTimeout &robot_receive_timeout=RobotReceiveTimeout::millisec(20))
Writes needed information to the robot to be read by the URCaps program.
Definition: reverse_interface.cpp:53
urcl::control::TrajectoryControlMessage::TRAJECTORY_NOOP
@ TRAJECTORY_NOOP
Represents no new control command.
urcl::control::ReverseInterface::keepalive_count_
uint32_t keepalive_count_
Definition: reverse_interface.h:183
urcl::control::ReverseInterface::writeFreedriveControlMessage
bool writeFreedriveControlMessage(const FreedriveControlMessage freedrive_action, const RobotReceiveTimeout &robot_receive_timeout=RobotReceiveTimeout::millisec(200))
Writes needed information to the robot to be read by the URScript program.
Definition: reverse_interface.cpp:161
urcl::control::FreedriveControlMessage::FREEDRIVE_START
@ FREEDRIVE_START
Represents command to start freedrive mode.
urcl::control::ReverseInterface::registerDisconnectionCallback
void registerDisconnectionCallback(std::function< void(const int)> disconnection_fun)
Definition: reverse_interface.h:144
urcl::vector6d_t
std::array< double, 6 > vector6d_t
Definition: types.h:30
urcl::control::ReverseInterface::connectionCallback
virtual void connectionCallback(const socket_t filedescriptor)
Definition: reverse_interface.cpp:215
urcl::RobotReceiveTimeout::millisec
static RobotReceiveTimeout millisec(const unsigned int milliseconds=20)
Create a RobotReceiveTimeout object with a specific timeout given in milliseconds.
Definition: robot_receive_timeout.cpp:44
urcl::control::TrajectoryControlMessage::TRAJECTORY_CANCEL
@ TRAJECTORY_CANCEL
Represents command to cancel currently active trajectory.
urcl::control::TrajectoryControlMessage
TrajectoryControlMessage
Control messages for forwarding and aborting trajectories.
Definition: reverse_interface.h:48
urcl::comm::ControlMode::MODE_IDLE
@ MODE_IDLE
Set when no controller is currently active controlling the robot.
urcl::control::ReverseInterface::messageCallback
virtual void messageCallback(const socket_t filedescriptor, char *buffer, int nbytesrecv)
Definition: reverse_interface.cpp:237
urcl::control::ReverseInterface::MAX_MESSAGE_LENGTH
static const int MAX_MESSAGE_LENGTH
Definition: reverse_interface.h:178
urcl::control::ReverseInterface::step_time_
std::chrono::milliseconds step_time_
Definition: reverse_interface.h:181
urcl::control::ReverseInterface::~ReverseInterface
virtual ~ReverseInterface()=default
Disconnects possible clients so the reverse interface object can be safely destroyed.
urcl::comm::TCPServer
Wrapper class for a TCP socket server.
Definition: tcp_server.h:58
urcl::control::ReverseInterface::client_fd_
socket_t client_fd_
Definition: reverse_interface.h:167
urcl::control::FreedriveControlMessage::FREEDRIVE_NOOP
@ FREEDRIVE_NOOP
Represents keep running in freedrive mode.
urcl::control::ReverseInterface::keep_alive_count_modified_deprecated_
bool keep_alive_count_modified_deprecated_
Definition: reverse_interface.h:184
urcl::control::ReverseInterface::handle_program_state_
std::function< void(bool)> handle_program_state_
Definition: reverse_interface.h:180
log.h
urcl::control::FreedriveControlMessage::FREEDRIVE_STOP
@ FREEDRIVE_STOP
Represents command to stop freedrive mode.
urcl::control::ReverseInterface::server_
comm::TCPServer server_
Definition: reverse_interface.h:168
urcl::control::ReverseInterface::writeTrajectoryControlMessage
bool writeTrajectoryControlMessage(const TrajectoryControlMessage trajectory_action, const int point_number=0, const RobotReceiveTimeout &robot_receive_timeout=RobotReceiveTimeout::millisec(200))
Writes needed information to the robot to be read by the URScript program.
Definition: reverse_interface.cpp:113
urcl::control::TrajectoryControlMessage::TRAJECTORY_START
@ TRAJECTORY_START
Represents command to start a new trajectory.
urcl::control::ReverseInterface::ReverseInterface
ReverseInterface()=delete
urcl::control::ReverseInterface::isConnected
bool isConnected() const
Checks if the reverse interface is connected to the robot.
Definition: reverse_interface.h:154
tcp_server.h
urcl::RobotReceiveTimeout
RobotReceiveTimeout class containing a timeout configuration.
Definition: robot_receive_timeout.h:47
urcl::control::FreedriveControlMessage
FreedriveControlMessage
Control messages for starting and stopping freedrive mode.
Definition: reverse_interface.h:58
endian.h


ur_client_library
Author(s): Thomas Timm Andersen, Simon Rasmussen, Felix Exner, Lea Steffen, Tristan Schnell
autogenerated on Mon May 26 2025 02:35:58