script_command_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 2021 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_SCRIPT_COMMAND_INTERFACE_H_INCLUDED
30 #define UR_CLIENT_LIBRARY_SCRIPT_COMMAND_INTERFACE_H_INCLUDED
31 
34 
35 namespace urcl
36 {
37 namespace control
38 {
42 enum class ToolContactResult : int32_t
43 {
44 
47 };
48 
56 {
57 public:
58  ScriptCommandInterface() = delete;
64  ScriptCommandInterface(uint32_t port);
65 
71  bool zeroFTSensor();
72 
82  bool setPayload(const double mass, const vector3d_t* cog);
83 
91  bool setToolVoltage(const ToolVoltage voltage);
92 
122  bool startForceMode(const vector6d_t* task_frame, const vector6uint32_t* selection_vector, const vector6d_t* wrench,
123  const unsigned int type, const vector6d_t* limits, double damping_factor,
124  double gain_scaling_factor);
125 
131  bool endForceMode();
132 
140  bool startToolContact();
141 
148  bool endToolContact();
149 
154  bool clientConnected();
155 
161  void setToolContactResultCallback(std::function<void(ToolContactResult)> callback)
162  {
163  handle_tool_contact_result_ = callback;
164  }
165 
166 protected:
167  virtual void connectionCallback(const socket_t filedescriptor) override;
168 
169  virtual void disconnectionCallback(const socket_t filedescriptor) override;
170 
171  virtual void messageCallback(const socket_t filedescriptor, char* buffer, int nbytesrecv) override;
172 
173 private:
177  enum class ScriptCommand : int32_t
178  {
179 
180  ZERO_FTSENSOR = 0,
181  SET_PAYLOAD = 1,
182  SET_TOOL_VOLTAGE = 2,
183  START_FORCE_MODE = 3,
184  END_FORCE_MODE = 4,
185  START_TOOL_CONTACT = 5,
186  END_TOOL_CONTACT = 6,
187  };
188 
190  static const int MAX_MESSAGE_LENGTH = 28;
191 
193 };
194 
195 } // namespace control
196 } // namespace urcl
197 
198 #endif // UR_CLIENT_LIBRARY_SCRIPT_COMMAND_INTERFACE_H_INCLUDED
socket_t
int socket_t
Definition: socket_t.h:57
urcl::control::ScriptCommandInterface::startToolContact
bool startToolContact()
This will make the robot look for tool contact in the tcp directions that the robot is currently movi...
Definition: script_command_interface.cpp:185
urcl::control::ScriptCommandInterface::ScriptCommand::END_FORCE_MODE
@ END_FORCE_MODE
End force mode.
urcl::control::ScriptCommandInterface::ScriptCommand::END_TOOL_CONTACT
@ END_TOOL_CONTACT
End detecting tool contact.
urcl::control::ScriptCommandInterface::messageCallback
virtual void messageCallback(const socket_t filedescriptor, char *buffer, int nbytesrecv) override
Definition: script_command_interface.cpp:252
urcl::control::ScriptCommandInterface::ScriptCommand::START_TOOL_CONTACT
@ START_TOOL_CONTACT
Start detecting tool contact.
urcl::ToolVoltage
ToolVoltage
Possible values for the tool voltage.
Definition: tool_communication.h:41
urcl
Definition: bin_parser.h:36
urcl::control::ScriptCommandInterface::setPayload
bool setPayload(const double mass, const vector3d_t *cog)
Set the active payload mass and center of gravity.
Definition: script_command_interface.cpp:60
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::ScriptCommandInterface::ScriptCommand::SET_PAYLOAD
@ SET_PAYLOAD
Set payload.
urcl::control::ScriptCommandInterface
The ScriptCommandInterface class starts a TCPServer for a robot to connect to and this connection is ...
Definition: script_command_interface.h:55
urcl::control::ScriptCommandInterface::disconnectionCallback
virtual void disconnectionCallback(const socket_t filedescriptor) override
Definition: script_command_interface.cpp:245
urcl::control::ScriptCommandInterface::ScriptCommandInterface
ScriptCommandInterface()=delete
urcl::control::ToolContactResult
ToolContactResult
Types for encoding until tool contact execution result.
Definition: script_command_interface.h:42
urcl::control::ScriptCommandInterface::setToolContactResultCallback
void setToolContactResultCallback(std::function< void(ToolContactResult)> callback)
Set the tool contact result callback object.
Definition: script_command_interface.h:161
urcl::control::ScriptCommandInterface::setToolVoltage
bool setToolVoltage(const ToolVoltage voltage)
Set the tool voltage.
Definition: script_command_interface.cpp:88
urcl::vector6d_t
std::array< double, 6 > vector6d_t
Definition: types.h:30
tool_communication.h
urcl::control::ScriptCommandInterface::startForceMode
bool startForceMode(const vector6d_t *task_frame, const vector6uint32_t *selection_vector, const vector6d_t *wrench, const unsigned int type, const vector6d_t *limits, double damping_factor, double gain_scaling_factor)
Set robot to be controlled in force mode.
Definition: script_command_interface.cpp:110
urcl::control::ScriptCommandInterface::endForceMode
bool endForceMode()
Stop force mode and put the robot into normal operation mode.
Definition: script_command_interface.cpp:165
urcl::control::ScriptCommandInterface::client_connected_
bool client_connected_
Definition: script_command_interface.h:189
urcl::control::ScriptCommandInterface::ScriptCommand::START_FORCE_MODE
@ START_FORCE_MODE
Start force mode.
urcl::vector6uint32_t
std::array< uint32_t, 6 > vector6uint32_t
Definition: types.h:32
urcl::control::ScriptCommandInterface::clientConnected
bool clientConnected()
Returns whether a client/robot is connected to this server.
Definition: script_command_interface.cpp:225
urcl::control::ScriptCommandInterface::ScriptCommand::ZERO_FTSENSOR
@ ZERO_FTSENSOR
Zero force torque sensor.
urcl::control::ScriptCommandInterface::endToolContact
bool endToolContact()
This will stop the robot from looking for a tool contact, it will also enable sending move commands t...
Definition: script_command_interface.cpp:205
urcl::control::ToolContactResult::UNTIL_TOOL_CONTACT_RESULT_CANCELED
@ UNTIL_TOOL_CONTACT_RESULT_CANCELED
Canceled by user.
urcl::control::ScriptCommandInterface::MAX_MESSAGE_LENGTH
static const int MAX_MESSAGE_LENGTH
Definition: script_command_interface.h:190
urcl::control::ScriptCommandInterface::ScriptCommand::SET_TOOL_VOLTAGE
@ SET_TOOL_VOLTAGE
Set tool voltage.
urcl::control::ScriptCommandInterface::connectionCallback
virtual void connectionCallback(const socket_t filedescriptor) override
Definition: script_command_interface.cpp:230
reverse_interface.h
urcl::control::ScriptCommandInterface::handle_tool_contact_result_
std::function< void(ToolContactResult)> handle_tool_contact_result_
Definition: script_command_interface.h:192
urcl::control::ToolContactResult::UNTIL_TOOL_CONTACT_RESULT_SUCCESS
@ UNTIL_TOOL_CONTACT_RESULT_SUCCESS
Successful execution.
urcl::vector3d_t
std::array< double, 3 > vector3d_t
Definition: types.h:29
urcl::control::ScriptCommandInterface::zeroFTSensor
bool zeroFTSensor()
Zero the force torque sensor.
Definition: script_command_interface.cpp:41
urcl::control::ScriptCommandInterface::ScriptCommand
ScriptCommand
Available script commands.
Definition: script_command_interface.h:177


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