ur_driver.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 #ifndef UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED
29 #define UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED
30 
31 #include <functional>
32 
42 
43 namespace urcl
44 {
52 class UrDriver
53 {
54 public:
97  UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
98  const std::string& input_recipe_file, std::function<void(bool)> handle_program_state, bool headless_mode,
99  std::unique_ptr<ToolCommSetup> tool_comm_setup, const uint32_t reverse_port = 50001,
100  const uint32_t script_sender_port = 50002, int servoj_gain = 2000, double servoj_lookahead_time = 0.03,
101  bool non_blocking_read = false, const std::string& reverse_ip = "", const uint32_t trajectory_port = 50003,
102  const uint32_t script_command_port = 50004, double force_mode_damping = 0.025,
103  double force_mode_gain_scaling = 0.5);
104 
134  UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
135  const std::string& input_recipe_file, std::function<void(bool)> handle_program_state, bool headless_mode,
136  std::unique_ptr<ToolCommSetup> tool_comm_setup, const std::string& calibration_checksum = "",
137  const uint32_t reverse_port = 50001, const uint32_t script_sender_port = 50002, int servoj_gain = 2000,
138  double servoj_lookahead_time = 0.03, bool non_blocking_read = false, const std::string& reverse_ip = "",
139  const uint32_t trajectory_port = 50003, const uint32_t script_command_port = 50004,
140  double force_mode_damping = 0.025, double force_mode_gain_scaling = 0.5);
170  UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
171  const std::string& input_recipe_file, std::function<void(bool)> handle_program_state, bool headless_mode,
172  const std::string& calibration_checksum = "", const uint32_t reverse_port = 50001,
173  const uint32_t script_sender_port = 50002, int servoj_gain = 2000, double servoj_lookahead_time = 0.03,
174  bool non_blocking_read = false, const std::string& reverse_ip = "", const uint32_t trajectory_port = 50003,
175  const uint32_t script_command_port = 50004, double force_mode_damping = 0.025,
176  double force_mode_gain_scaling = 0.5)
177  : UrDriver(robot_ip, script_file, output_recipe_file, input_recipe_file, handle_program_state, headless_mode,
178  std::unique_ptr<ToolCommSetup>{}, calibration_checksum, reverse_port, script_sender_port, servoj_gain,
179  servoj_lookahead_time, non_blocking_read, reverse_ip, trajectory_port, script_command_port,
180  force_mode_damping, force_mode_gain_scaling)
181  {
182  }
183 
184  virtual ~UrDriver() = default;
185 
193  std::unique_ptr<rtde_interface::DataPackage> getDataPackage();
194 
195  uint32_t getControlFrequency() const
196  {
197  return rtde_frequency_;
198  }
199 
209  bool writeJointCommand(const vector6d_t& values, const comm::ControlMode control_mode);
210 
221  bool writeTrajectoryPoint(const vector6d_t& positions, const bool cartesian, const float goal_time = 0.0,
222  const float blend_radius = 0.052);
223 
234  bool writeTrajectorySplinePoint(const vector6d_t& positions, const vector6d_t& velocities,
235  const vector6d_t& accelerations, const float goal_time = 0.0);
236 
246  bool writeTrajectorySplinePoint(const vector6d_t& positions, const vector6d_t& velocities,
247  const float goal_time = 0.0);
248 
257  bool writeTrajectorySplinePoint(const vector6d_t& positions, const float goal_time = 0.0);
258 
268  const int point_number = 0);
269 
278 
285  bool zeroFTSensor();
286 
297  bool setPayload(const float mass, const vector3d_t& cog);
298 
307  bool setToolVoltage(const ToolVoltage voltage);
308 
330  bool startForceMode(const vector6d_t& task_frame, const vector6uint32_t& selection_vector, const vector6d_t& wrench,
331  const unsigned int type, const vector6d_t& limits);
332 
338  bool endForceMode();
339 
347  bool startToolContact();
348 
355  bool endToolContact();
356 
365  bool writeKeepalive();
366 
373  void startRTDECommunication();
374 
381  bool stopControl();
382 
391  bool checkCalibration(const std::string& checksum);
392 
399 
409  bool sendScript(const std::string& program);
410 
418  bool sendRobotProgram();
419 
424  {
425  return robot_version_;
426  }
427 
433  std::vector<std::string> getRTDEOutputRecipe();
434 
440  void setKeepaliveCount(const uint32_t& count);
441 
451  void registerTrajectoryDoneCallback(std::function<void(control::TrajectoryResult)> trajectory_done_cb)
452  {
453  trajectory_interface_->setTrajectoryEndCallback(trajectory_done_cb);
454  }
455 
464  void registerToolContactResultCallback(std::function<void(control::ToolContactResult)> tool_contact_result_cb)
465  {
466  script_command_interface_->setToolContactResultCallback(tool_contact_result_cb);
467  }
468 
469 private:
470  std::string readScriptFile(const std::string& filename);
471 
474  std::unique_ptr<rtde_interface::RTDEClient> rtde_client_;
475  std::unique_ptr<control::ReverseInterface> reverse_interface_;
476  std::unique_ptr<control::TrajectoryPointInterface> trajectory_interface_;
477  std::unique_ptr<control::ScriptCommandInterface> script_command_interface_;
478  std::unique_ptr<control::ScriptSender> script_sender_;
479  std::unique_ptr<comm::URStream<primary_interface::PrimaryPackage>> primary_stream_;
480  std::unique_ptr<comm::URStream<primary_interface::PrimaryPackage>> secondary_stream_;
481 
482  double servoj_time_;
483  uint32_t servoj_gain_;
485 
486  std::function<void(bool)> handle_program_state_;
487 
488  std::string robot_ip_;
490  std::string full_robot_program_;
491 
494 
496 };
497 } // namespace urcl
498 #endif // ifndef UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED
bool in_headless_mode_
Definition: ur_driver.h:489
std::unique_ptr< control::ReverseInterface > reverse_interface_
Definition: ur_driver.h:475
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, const uint32_t script_command_port=50004, double force_mode_damping=0.025, double force_mode_gain_scaling=0.5)
Constructs a new UrDriver object. Upon initialization this class will check the calibration checksum ...
Definition: ur_driver.cpp:55
This is the main class for interfacing the driver.
Definition: ur_driver.h:52
ToolVoltage
Possible values for the tool voltage.
bool non_blocking_read_
Definition: ur_driver.h:493
TrajectoryResult
Types for encoding trajectory execution result.
bool writeJointCommand(const vector6d_t &values, const comm::ControlMode control_mode)
Writes a joint command together with a keepalive signal onto the socket being sent to the robot...
Definition: ur_driver.cpp:262
comm::INotifier notifier_
Definition: ur_driver.h:473
VersionInformation robot_version_
Definition: ur_driver.h:495
FreedriveControlMessage
Control messages for starting and stopping freedrive mode.
std::string readScriptFile(const std::string &filename)
Definition: ur_driver.cpp:494
std::vector< std::string > getRTDEOutputRecipe()
Getter for the RTDE output recipe used in the RTDE client.
Definition: ur_driver.cpp:572
bool sendRobotProgram()
Sends the external control program to the robot.
Definition: ur_driver.cpp:559
bool endToolContact()
This will stop the robot from looking for a tool contact, it will also enable sending move commands t...
Definition: ur_driver.cpp:454
Struct containing a robot&#39;s version information.
uint32_t servoj_gain_
Definition: ur_driver.h:483
bool writeTrajectorySplinePoint(const vector6d_t &positions, const vector6d_t &velocities, const vector6d_t &accelerations, const float goal_time=0.0)
Writes a trajectory spline point for quintic spline interpolation onto the dedicated socket...
Definition: ur_driver.cpp:273
std::array< double, 3 > vector3d_t
Definition: types.h:29
void startRTDECommunication()
Starts the RTDE communication.
Definition: ur_driver.cpp:483
bool setPayload(const float mass, const vector3d_t &cog)
Set the payload mass and center of gravity. Note: It requires the external control script to be runni...
Definition: ur_driver.cpp:329
The RTDEWriter class offers an abstraction layer to send data to the robot via the RTDE interface...
Definition: rtde_writer.h:49
bool stopControl()
Sends a stop command to the socket interface which will signal the program running on the robot to no...
Definition: ur_driver.cpp:488
std::unique_ptr< control::ScriptSender > script_sender_
Definition: ur_driver.h:478
const VersionInformation & getVersion()
Returns version information about the currently connected robot.
Definition: ur_driver.h:423
std::function< void(bool)> handle_program_state_
Definition: ur_driver.h:486
std::unique_ptr< control::ScriptCommandInterface > script_command_interface_
Definition: ur_driver.h:477
std::unique_ptr< control::TrajectoryPointInterface > trajectory_interface_
Definition: ur_driver.h:476
void registerToolContactResultCallback(std::function< void(control::ToolContactResult)> tool_contact_result_cb)
Register a callback for the robot-based tool contact execution completion.
Definition: ur_driver.h:464
rtde_interface::RTDEWriter & getRTDEWriter()
Getter for the RTDE writer used to write to the robot&#39;s RTDE interface.
Definition: ur_driver.cpp:527
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, const uint32_t script_command_port=50004, double force_mode_damping=0.025, double force_mode_gain_scaling=0.5)
Constructs a new UrDriver object.
Definition: ur_driver.h:170
Parent class for notifiers.
Definition: pipeline.h:210
std::string full_robot_program_
Definition: ur_driver.h:490
bool writeKeepalive()
Write a keepalive signal only.
Definition: ur_driver.cpp:477
uint32_t getControlFrequency() const
Definition: ur_driver.h:195
bool sendScript(const std::string &program)
Sends a custom script program to the robot.
Definition: ur_driver.cpp:532
std::unique_ptr< comm::URStream< primary_interface::PrimaryPackage > > primary_stream_
Definition: ur_driver.h:479
bool setToolVoltage(const ToolVoltage voltage)
Set the tool voltage. Note: It requires the external control script to be running or the robot to be ...
Definition: ur_driver.cpp:348
virtual ~UrDriver()=default
bool zeroFTSensor()
Zero the force torque sensor (only availbe on e-Series). Note: It requires the external control scrip...
Definition: ur_driver.cpp:301
ControlMode
Control modes as interpreted from the script runnning on the robot.
Definition: control_mode.h:39
bool startForceMode(const vector6d_t &task_frame, const vector6uint32_t &selection_vector, const vector6d_t &wrench, const unsigned int type, const vector6d_t &limits)
Start the robot to be controlled in force mode.
Definition: ur_driver.cpp:380
std::unique_ptr< rtde_interface::DataPackage > getDataPackage()
Access function to receive the latest data package sent from the robot through RTDE interface...
Definition: ur_driver.cpp:252
bool writeTrajectoryPoint(const vector6d_t &positions, const bool cartesian, const float goal_time=0.0, const float blend_radius=0.052)
Writes a trajectory point onto the dedicated socket.
Definition: ur_driver.cpp:267
int get_packet_timeout_
Definition: ur_driver.h:492
bool startToolContact()
This will make the robot look for tool contact in the tcp directions that the robot is currently movi...
Definition: ur_driver.cpp:431
std::unique_ptr< rtde_interface::RTDEClient > rtde_client_
Definition: ur_driver.h:474
bool writeFreedriveControlMessage(const control::FreedriveControlMessage freedrive_action)
Writes a control message in freedrive mode.
Definition: ur_driver.cpp:296
int rtde_frequency_
Definition: ur_driver.h:472
TrajectoryControlMessage
Control messages for forwarding and aborting trajectories.
bool writeTrajectoryControlMessage(const control::TrajectoryControlMessage trajectory_action, const int point_number=0)
Writes a control message in trajectory forward mode.
Definition: ur_driver.cpp:290
double servoj_time_
Definition: ur_driver.h:482
bool checkCalibration(const std::string &checksum)
Checks if the kinematics information in the used model fits the actual robot.
Definition: ur_driver.cpp:502
double servoj_lookahead_time_
Definition: ur_driver.h:484
ToolContactResult
Types for encoding until tool contact execution result.
std::string robot_ip_
Definition: ur_driver.h:488
std::array< uint32_t, 6 > vector6uint32_t
Definition: types.h:32
std::array< double, 6 > vector6d_t
Definition: types.h:30
void registerTrajectoryDoneCallback(std::function< void(control::TrajectoryResult)> trajectory_done_cb)
Register a callback for the robot-based trajectory execution completion.
Definition: ur_driver.h:451
std::unique_ptr< comm::URStream< primary_interface::PrimaryPackage > > secondary_stream_
Definition: ur_driver.h:480
Class holding a tool communication configuration.
void setKeepaliveCount(const uint32_t &count)
Set the Keepalive count. This will set the number of allowed timeout reads on the robot...
Definition: ur_driver.cpp:577
bool endForceMode()
Stop force mode and put the robot into normal operation mode.
Definition: ur_driver.cpp:418


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