Public Member Functions | Protected Member Functions | Private Types | Private Attributes | Static Private Attributes | List of all members
urcl::control::ScriptCommandInterface Class Reference

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. More...

#include <script_command_interface.h>

Inheritance diagram for urcl::control::ScriptCommandInterface:
Inheritance graph
[legend]

Public Member Functions

bool clientConnected ()
 Returns whether a client/robot is connected to this server. More...
 
bool endForceMode ()
 Stop force mode and put the robot into normal operation mode. More...
 
bool endToolContact ()
 This will stop the robot from looking for a tool contact, it will also enable sending move commands to the robot again if the robot's tool is in contact. More...
 
 ScriptCommandInterface ()=delete
 
 ScriptCommandInterface (uint32_t port)
 Creates a ScriptCommandInterface object, including a new TCPServer. More...
 
bool setPayload (const double mass, const vector3d_t *cog)
 Set the active payload mass and center of gravity. More...
 
void setToolContactResultCallback (std::function< void(ToolContactResult)> callback)
 Set the tool contact result callback object. More...
 
bool setToolVoltage (const ToolVoltage voltage)
 Set the tool voltage. More...
 
bool startForceMode (const vector6d_t *task_frame, const vector6uint32_t *selection_vector, const vector6d_t *wrench, const unsigned int type, const vector6d_t *limits)
 Set robot to be controlled in force mode. More...
 
bool startToolContact ()
 This will make the robot look for tool contact in the tcp directions that the robot is currently moving. Once a tool contact has been detected all movements will be canceled. Call endToolContact to enable movements again. More...
 
bool zeroFTSensor ()
 Zero the force torque sensor. More...
 
- Public Member Functions inherited from urcl::control::ReverseInterface
 ReverseInterface ()=delete
 
 ReverseInterface (uint32_t port, std::function< void(bool)> handle_program_state)
 Creates a ReverseInterface object including a TCPServer. More...
 
virtual void setKeepaliveCount (const uint32_t &count)
 Set the Keepalive count. This will set the number of allowed timeout reads on the robot. More...
 
virtual bool write (const vector6d_t *positions, const comm::ControlMode control_mode=comm::ControlMode::MODE_IDLE)
 Writes needed information to the robot to be read by the URCaps program. More...
 
bool writeFreedriveControlMessage (const FreedriveControlMessage freedrive_action)
 Writes needed information to the robot to be read by the URScript program. More...
 
bool writeTrajectoryControlMessage (const TrajectoryControlMessage trajectory_action, const int point_number=0)
 Writes needed information to the robot to be read by the URScript program. More...
 
virtual ~ReverseInterface ()=default
 Disconnects possible clients so the reverse interface object can be safely destroyed. More...
 

Protected Member Functions

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
 
- Protected Member Functions inherited from urcl::control::ReverseInterface
template<typename T >
size_t append (uint8_t *buffer, T &val)
 

Private Types

enum  ScriptCommand : int32_t {
  ScriptCommand::ZERO_FTSENSOR = 0, ScriptCommand::SET_PAYLOAD = 1, ScriptCommand::SET_TOOL_VOLTAGE = 2, ScriptCommand::START_FORCE_MODE = 3,
  ScriptCommand::END_FORCE_MODE = 4, ScriptCommand::START_TOOL_CONTACT = 5, ScriptCommand::END_TOOL_CONTACT = 6
}
 Available script commands. More...
 

Private Attributes

bool client_connected_
 
std::function< void(ToolContactResult)> handle_tool_contact_result_
 

Static Private Attributes

static const int MAX_MESSAGE_LENGTH = 26
 

Additional Inherited Members

- Static Public Attributes inherited from urcl::control::ReverseInterface
static const int32_t MULT_JOINTSTATE = 1000000
 
- Protected Attributes inherited from urcl::control::ReverseInterface
int client_fd_
 
std::function< void(bool)> handle_program_state_
 
uint32_t keepalive_count_
 
comm::TCPServer server_
 
- Static Protected Attributes inherited from urcl::control::ReverseInterface
static const int MAX_MESSAGE_LENGTH = 8
 

Detailed Description

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 separate thread in the external control script.

Definition at line 55 of file script_command_interface.h.

Member Enumeration Documentation

◆ ScriptCommand

Available script commands.

Enumerator
ZERO_FTSENSOR 

Zero force torque sensor.

SET_PAYLOAD 

Set payload.

SET_TOOL_VOLTAGE 

Set tool voltage.

START_FORCE_MODE 

Start force mode.

END_FORCE_MODE 

End force mode.

START_TOOL_CONTACT 

Start detecting tool contact.

END_TOOL_CONTACT 

End detecting tool contact.

Definition at line 168 of file script_command_interface.h.

Constructor & Destructor Documentation

◆ ScriptCommandInterface() [1/2]

urcl::control::ScriptCommandInterface::ScriptCommandInterface ( )
delete

◆ ScriptCommandInterface() [2/2]

urcl::control::ScriptCommandInterface::ScriptCommandInterface ( uint32_t  port)

Creates a ScriptCommandInterface object, including a new TCPServer.

Parameters
portPort to start the server on

Definition at line 35 of file script_command_interface.cpp.

Member Function Documentation

◆ clientConnected()

bool urcl::control::ScriptCommandInterface::clientConnected ( )

Returns whether a client/robot is connected to this server.

Definition at line 217 of file script_command_interface.cpp.

◆ connectionCallback()

void urcl::control::ScriptCommandInterface::connectionCallback ( const int  filedescriptor)
overrideprotectedvirtual

Reimplemented from urcl::control::ReverseInterface.

Definition at line 222 of file script_command_interface.cpp.

◆ disconnectionCallback()

void urcl::control::ScriptCommandInterface::disconnectionCallback ( const int  filedescriptor)
overrideprotectedvirtual

Reimplemented from urcl::control::ReverseInterface.

Definition at line 237 of file script_command_interface.cpp.

◆ endForceMode()

bool urcl::control::ScriptCommandInterface::endForceMode ( )

Stop force mode and put the robot into normal operation mode.

Returns
True, if the write was performed successfully, false otherwise.

Definition at line 157 of file script_command_interface.cpp.

◆ endToolContact()

bool urcl::control::ScriptCommandInterface::endToolContact ( )

This will stop the robot from looking for a tool contact, it will also enable sending move commands to the robot again if the robot's tool is in contact.

Returns
True, if the write was performed successfully, false otherwise.

Definition at line 197 of file script_command_interface.cpp.

◆ messageCallback()

void urcl::control::ScriptCommandInterface::messageCallback ( const int  filedescriptor,
char *  buffer,
int  nbytesrecv 
)
overrideprotectedvirtual

Reimplemented from urcl::control::ReverseInterface.

Definition at line 244 of file script_command_interface.cpp.

◆ setPayload()

bool urcl::control::ScriptCommandInterface::setPayload ( const double  mass,
const vector3d_t cog 
)

Set the active payload mass and center of gravity.

Parameters
massmass in kilograms
cogCenter 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.

Definition at line 59 of file script_command_interface.cpp.

◆ setToolContactResultCallback()

void urcl::control::ScriptCommandInterface::setToolContactResultCallback ( std::function< void(ToolContactResult)>  callback)
inline

Set the tool contact result callback object.

Parameters
callbackCallback function that will be triggered when the robot enters tool contact

Definition at line 152 of file script_command_interface.h.

◆ setToolVoltage()

bool urcl::control::ScriptCommandInterface::setToolVoltage ( const ToolVoltage  voltage)

Set the tool voltage.

Parameters
voltageTool voltage
Returns
True, if the write was performed successfully, false otherwise.

Definition at line 87 of file script_command_interface.cpp.

◆ startForceMode()

bool urcl::control::ScriptCommandInterface::startForceMode ( const vector6d_t task_frame,
const vector6uint32_t selection_vector,
const vector6d_t wrench,
const unsigned int  type,
const vector6d_t limits 
)

Set robot to be controlled in force mode.

Parameters
task_frameA pose vector that defines the force frame relative to the base frame
selection_vectorA 6d vector of 0s and 1s. 1 means that the robot will be compliant in the corresponding axis of the task frame
wrenchThe forces/torques the robot will apply to its environment. The robot adjusts its position along/about compliant axis in order to achieve the specified force/torque. Values have no effect for non-compliant axes
typeAn integer [1;3] specifying how the robot interprets the force frame 1: The force frame is transformed in a way such that its y-axis is aligned with a vector pointing from the robot tcp towards the origin of the force frame 2: The force frame is not transformed. 3: The force frame is transformed in a way such that its x-axis is the projection of the robot tcp velocity vector onto the x-y plane of the force frame
limits(Float) 6d vector. For compliant axes, these values are the maximum allowed tcp speed along/about the axis. For non-compliant axes, these values are the maximum allowed deviation along/about an axis between the actual tcp position and the one set by the program
Returns
True, if the write was performed successfully, false otherwise.

Definition at line 109 of file script_command_interface.cpp.

◆ startToolContact()

bool urcl::control::ScriptCommandInterface::startToolContact ( )

This will make the robot look for tool contact in the tcp directions that the robot is currently moving. Once a tool contact has been detected all movements will be canceled. Call endToolContact to enable movements again.

Returns
True, if the write was performed successfully, false otherwise.

Definition at line 177 of file script_command_interface.cpp.

◆ zeroFTSensor()

bool urcl::control::ScriptCommandInterface::zeroFTSensor ( )

Zero the force torque sensor.

Returns
True, if the write was performed successfully, false otherwise.

Definition at line 40 of file script_command_interface.cpp.

Member Data Documentation

◆ client_connected_

bool urcl::control::ScriptCommandInterface::client_connected_
private

Definition at line 180 of file script_command_interface.h.

◆ handle_tool_contact_result_

std::function<void(ToolContactResult)> urcl::control::ScriptCommandInterface::handle_tool_contact_result_
private

Definition at line 183 of file script_command_interface.h.

◆ MAX_MESSAGE_LENGTH

const int urcl::control::ScriptCommandInterface::MAX_MESSAGE_LENGTH = 26
staticprivate

Definition at line 181 of file script_command_interface.h.


The documentation for this class was generated from the following files:


ur_client_library
Author(s): Thomas Timm Andersen, Simon Rasmussen, Felix Exner, Lea Steffen, Tristan Schnell
autogenerated on Tue Jul 4 2023 02:09:47