Skip to content

Commit

Permalink
Added interface for forwarding script commands to the robot, that is … (
Browse files Browse the repository at this point in the history
#111)

* Added interface for forwarding script commands to the robot, that is then executed locally on the robot

This allows the user to be able to zero ftsensor, set payload and set tool voltage when the robot is in local control.

* Added voltage check to setToolVoltage

* Add warnings when falling back to plain script code

* Fix syntax

Co-authored-by: Felix Exner <[email protected]>

* Made scriptCommand private and return false in setToolVoltage instead throwing an exception

Co-authored-by: Felix Exner <[email protected]>
Co-authored-by: Felix Exner <[email protected]>
  • Loading branch information
3 people authored Sep 26, 2022
1 parent f31f998 commit ba604f7
Show file tree
Hide file tree
Showing 6 changed files with 421 additions and 5 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ add_library(urcl SHARED
src/control/reverse_interface.cpp
src/control/script_sender.cpp
src/control/trajectory_point_interface.cpp
src/control/script_command_interface.cpp
src/primary/primary_package.cpp
src/primary/robot_message.cpp
src/primary/robot_state.cpp
Expand Down
114 changes: 114 additions & 0 deletions include/ur_client_library/control/script_command_interface.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,114 @@
// 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 ------------------------------------------------

//----------------------------------------------------------------------
/*!\file
*
* \author Mads Holm Peters [email protected]
* \date 2022-08-12
*
*/
//----------------------------------------------------------------------

#ifndef UR_CLIENT_LIBRARY_SCRIPT_COMMAND_INTERFACE_H_INCLUDED
#define UR_CLIENT_LIBRARY_SCRIPT_COMMAND_INTERFACE_H_INCLUDED

#include "ur_client_library/control/reverse_interface.h"
#include "ur_client_library/ur/tool_communication.h"

namespace urcl
{
namespace control
{
/*!
* \brief The ScriptCommandInterface class starts a TCPServer for a robot to connect to and this connection is then used
* to forward script commands to the robot, which will be executed locally on the robot.
*
* The script commands will be executed in a seperate thread in the external control script.
*/
class ScriptCommandInterface : public ReverseInterface
{
public:
ScriptCommandInterface() = delete;
/*!
* \brief Creates a ScriptCommandInterface object, including a new TCPServer
*
* \param port Port to start the server on
*/
ScriptCommandInterface(uint32_t port);

/*!
* \brief Zero the force torque sensor
*
* \returns True, if the write was performed successfully, false otherwise.
*/
bool zeroFTSensor();

/*!
* \brief Set the active payload mass and center of gravity
*
* \param mass mass in kilograms
* \param cog Center of Gravity, a vector [CoGx, CoGy, CoGz] specifying the displacement (in meters) from the
* toolmount
*
* \returns True, if the write was performed successfully, false otherwise.
*/
bool setPayload(const double mass, const vector3d_t* cog);

/*!
* \brief Set the tool voltage.
*
* \param voltage Tool voltage
*
* \returns True, if the write was performed successfully, false otherwise.
*/
bool setToolVoltage(const ToolVoltage voltage);

/*!
* \brief Returns whether a client/robot is connected to this server.
*/
bool clientConnected();

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:
/*!
* \brief Available script commands
*/
enum class ScriptCommand : int32_t
{

ZERO_FTSENSOR = 0, ///< Zero force torque sensor
SET_PAYLOAD = 1, ///< Set payload
SET_TOOL_VOLTAGE = 2, ///< Set tool voltage
};

bool client_connected_;
static const int MAX_MESSAGE_LENGTH = 5;
};

} // namespace control
} // namespace urcl

#endif // UR_CLIENT_LIBRARY_SCRIPT_COMMAND_INTERFACE_H_INCLUDED
46 changes: 43 additions & 3 deletions include/ur_client_library/ur/ur_driver.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
#include "ur_client_library/rtde/rtde_client.h"
#include "ur_client_library/control/reverse_interface.h"
#include "ur_client_library/control/trajectory_point_interface.h"
#include "ur_client_library/control/script_command_interface.h"
#include "ur_client_library/control/script_sender.h"
#include "ur_client_library/ur/tool_communication.h"
#include "ur_client_library/ur/version_information.h"
Expand Down Expand Up @@ -88,12 +89,15 @@ class UrDriver
* address of the interface that is used for connecting to the robot's RTDE port will be used.
* \param trajectory_port Port used for sending trajectory points to the robot in case of
* trajectory forwarding.
* \param script_command_port Port used for forwarding script commands to the robot. The script commands will be
* executed locally on the robot.
*/
UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
const std::string& input_recipe_file, std::function<void(bool)> handle_program_state, bool headless_mode,
std::unique_ptr<ToolCommSetup> tool_comm_setup, const uint32_t reverse_port = 50001,
const uint32_t script_sender_port = 50002, int servoj_gain = 2000, double servoj_lookahead_time = 0.03,
bool non_blocking_read = false, const std::string& reverse_ip = "", const uint32_t trajectory_port = 50003);
bool non_blocking_read = false, const std::string& reverse_ip = "", const uint32_t trajectory_port = 50003,
const uint32_t script_command_port = 50004);

/*!
* \brief Constructs a new UrDriver object.
Expand All @@ -119,13 +123,15 @@ class UrDriver
* address of the interface that is used for connecting to the robot's RTDE port will be used.
* \param trajectory_port Port used for sending trajectory points to the robot in case of
* trajectory forwarding.
* \param script_command_port Port used for forwarding script commands to the robot. The script commands will be
* executed locally on the robot.
*/
UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
const std::string& input_recipe_file, std::function<void(bool)> handle_program_state, bool headless_mode,
std::unique_ptr<ToolCommSetup> tool_comm_setup, const std::string& calibration_checksum = "",
const uint32_t reverse_port = 50001, const uint32_t script_sender_port = 50002, int servoj_gain = 2000,
double servoj_lookahead_time = 0.03, bool non_blocking_read = false, const std::string& reverse_ip = "",
const uint32_t trajectory_port = 50003);
const uint32_t trajectory_port = 50003, const uint32_t script_command_port = 50004);
/*!
* \brief Constructs a new UrDriver object.
*
Expand All @@ -150,12 +156,15 @@ class UrDriver
* address of the interface that is used for connecting to the robot's RTDE port will be used.
* \param trajectory_port Port used for sending trajectory points to the robot in case of
* trajectory forwarding.
* \param script_command_port Port used for forwarding script commands to the robot. The script commands will be
* executed locally on the robot.
*/
UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
const std::string& input_recipe_file, std::function<void(bool)> handle_program_state, bool headless_mode,
const std::string& calibration_checksum = "", const uint32_t reverse_port = 50001,
const uint32_t script_sender_port = 50002, int servoj_gain = 2000, double servoj_lookahead_time = 0.03,
bool non_blocking_read = false, const std::string& reverse_ip = "", const uint32_t trajectory_port = 50003)
bool non_blocking_read = false, const std::string& reverse_ip = "", const uint32_t trajectory_port = 50003,
const uint32_t script_command_port = 50004)
: UrDriver(robot_ip, script_file, output_recipe_file, input_recipe_file, handle_program_state, headless_mode,
std::unique_ptr<ToolCommSetup>{}, calibration_checksum, reverse_port, script_sender_port, servoj_gain,
servoj_lookahead_time, non_blocking_read, reverse_ip)
Expand Down Expand Up @@ -213,6 +222,36 @@ class UrDriver
bool writeTrajectoryControlMessage(const control::TrajectoryControlMessage trajectory_action,
const int point_number = 0);

/*!
* \brief Zero the force torque sensor (only availbe on e-Series). Note: It requires the external control script to
* be running or the robot to be in headless mode
*
* \returns True on successful write.
*/
bool zeroFTSensor();

/*!
* \brief Set the payload mass and center of gravity. Note: It requires the external control script to be running or
* the robot to be in headless mode.
*
* \param mass mass in kilograms
* \param cog Center of Gravity, a vector [CoGx, CoGy, CoGz] specifying the displacement (in meters) from the
* toolmount
*
* \returns True on successful write.
*/
bool setPayload(const float mass, const vector3d_t& cog);

/*!
* \brief Set the tool voltage. Note: It requires the external control script to be running or the robot to be in
* headless mode.
*
* \param voltage tool voltage.
*
* \returns True on successful write.
*/
bool setToolVoltage(const ToolVoltage voltage);

/*!
* \brief Write a keepalive signal only.
*
Expand Down Expand Up @@ -320,6 +359,7 @@ class UrDriver
std::unique_ptr<rtde_interface::RTDEClient> rtde_client_;
std::unique_ptr<control::ReverseInterface> reverse_interface_;
std::unique_ptr<control::TrajectoryPointInterface> trajectory_interface_;
std::unique_ptr<control::ScriptCommandInterface> script_command_interface_;
std::unique_ptr<control::ScriptSender> script_sender_;
std::unique_ptr<comm::URStream<primary_interface::PrimaryPackage>> primary_stream_;
std::unique_ptr<comm::URStream<primary_interface::PrimaryPackage>> secondary_stream_;
Expand Down
30 changes: 30 additions & 0 deletions resources/external_control.urscript
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,11 @@ TRAJECTORY_RESULT_SUCCESS = 0
TRAJECTORY_RESULT_CANCELED = 1
TRAJECTORY_RESULT_FAILURE = 2

ZERO_FTSENSOR = 0
SET_PAYLOAD = 1
SET_TOOL_VOLTAGE = 2
SCRIPT_COMMAND_DATA_DIMENSION = 5

#Global variables are also showed in the Teach pendants variable list
global cmd_servo_state = SERVO_UNINITIALIZED
global cmd_servo_qd = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
Expand Down Expand Up @@ -213,13 +218,34 @@ def set_servo_pose(pose):
cmd_servo_q = get_inverse_kin(pose, cmd_servo_q)
end

# Thread to receive script commands
thread script_commands():
while control_mode > MODE_STOPPED:
raw_command = socket_read_binary_integer(SCRIPT_COMMAND_DATA_DIMENSION, "script_command_socket", 0)
if raw_command[0] > 0:
command = raw_command[1]
if command == ZERO_FTSENSOR:
zero_ftsensor()
elif command == SET_PAYLOAD:
mass = raw_command[2] / MULT_jointstate
cog = [raw_command[3] / MULT_jointstate, raw_command[4] / MULT_jointstate, raw_command[5] / MULT_jointstate]
set_payload(mass, cog)
elif command == SET_TOOL_VOLTAGE:
tool_voltage = raw_command[2] / MULT_jointstate
set_tool_voltage(tool_voltage)
end
end
end
end


# HEADER_END

# NODE_CONTROL_LOOP_BEGINS

socket_open("{{SERVER_IP_REPLACE}}", {{SERVER_PORT_REPLACE}}, "reverse_socket")
socket_open("{{SERVER_IP_REPLACE}}", {{TRAJECTORY_SERVER_PORT_REPLACE}}, "trajectory_socket")
socket_open("{{SERVER_IP_REPLACE}}", {{SCRIPT_COMMAND_SERVER_PORT_REPLACE}}, "script_command_socket")

control_mode = MODE_UNINITIALIZED
thread_move = 0
Expand All @@ -229,6 +255,7 @@ global keepalive = -2
params_mult = socket_read_binary_integer(1+6+1, "reverse_socket", 0)
textmsg("ExternalControl: External control active")
keepalive = params_mult[1]
thread_script_commands = run script_commands()
while keepalive > 0 and control_mode > MODE_STOPPED:
enter_critical
params_mult = socket_read_binary_integer(1+6+1, "reverse_socket", 0.02) # steptime could work as well, but does not work in simulation
Expand Down Expand Up @@ -288,8 +315,11 @@ textmsg("ExternalControl: Stopping communication and control")
control_mode = MODE_STOPPED
join thread_move
join thread_trajectory
kill thread_script_commands
join thread_script_commands
textmsg("ExternalControl: All threads ended")
socket_close("reverse_socket")
socket_close("trajectory_socket")
socket_close("script_command_socket")

# NODE_CONTROL_LOOP_ENDS
Loading

0 comments on commit ba604f7

Please sign in to comment.