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 //
6 // Licensed under the Apache License, Version 2.0 (the "License");
7 // you may not use this file except in compliance with the License.
8 // You may obtain a copy of the License at
9 //
10 // http://www.apache.org/licenses/LICENSE-2.0
11 //
12 // Unless required by applicable law or agreed to in writing, software
13 // distributed under the License is distributed on an "AS IS" BASIS,
14 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 // See the License for the specific language governing permissions and
16 // limitations under the License.
17 // -- END LICENSE BLOCK ------------------------------------------------
18 
19 //----------------------------------------------------------------------
26 //----------------------------------------------------------------------
27 #ifndef UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED
28 #define UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED
29 
30 #include <functional>
31 
39 
40 namespace urcl
41 {
49 class UrDriver
50 {
51 public:
87  UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
88  const std::string& input_recipe_file, std::function<void(bool)> handle_program_state, bool headless_mode,
89  std::unique_ptr<ToolCommSetup> tool_comm_setup, const std::string& calibration_checksum = "",
90  const uint32_t reverse_port = 50001, const uint32_t script_sender_port = 50002, int servoj_gain = 2000,
91  double servoj_lookahead_time = 0.03, bool non_blocking_read = false);
113  UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
114  const std::string& input_recipe_file, std::function<void(bool)> handle_program_state, bool headless_mode,
115  const std::string& calibration_checksum = "", const uint32_t reverse_port = 50001,
116  const uint32_t script_sender_port = 50002, int servoj_gain = 2000, double servoj_lookahead_time = 0.03,
117  bool non_blocking_read = false)
118  : UrDriver(robot_ip, script_file, output_recipe_file, input_recipe_file, handle_program_state, headless_mode,
119  std::unique_ptr<ToolCommSetup>{}, calibration_checksum, reverse_port, script_sender_port, servoj_gain,
120  servoj_lookahead_time, non_blocking_read)
121  {
122  }
123 
124  virtual ~UrDriver() = default;
125 
133  std::unique_ptr<rtde_interface::DataPackage> getDataPackage();
134 
135  uint32_t getControlFrequency() const
136  {
137  return rtde_frequency_;
138  }
139 
149  bool writeJointCommand(const vector6d_t& values, const comm::ControlMode control_mode);
150 
159  bool writeKeepalive();
160 
167  void startRTDECommunication();
168 
175  bool stopControl();
176 
182  void checkCalibration(const std::string& checksum);
183 
190 
200  bool sendScript(const std::string& program);
201 
209  bool sendRobotProgram();
210 
215  {
216  return robot_version_;
217  }
218 
224  std::vector<std::string> getRTDEOutputRecipe();
225 
231  void setKeepaliveCount(const uint32_t& count);
232 
233 private:
234  std::string readScriptFile(const std::string& filename);
235 
238  std::unique_ptr<rtde_interface::RTDEClient> rtde_client_;
239  std::unique_ptr<comm::ReverseInterface> reverse_interface_;
240  std::unique_ptr<comm::ScriptSender> script_sender_;
241  std::unique_ptr<comm::URStream<primary_interface::PrimaryPackage>> primary_stream_;
242  std::unique_ptr<comm::URStream<primary_interface::PrimaryPackage>> secondary_stream_;
243 
244  double servoj_time_;
245  uint32_t servoj_gain_;
247 
248  std::function<void(bool)> handle_program_state_;
249 
250  std::string robot_ip_;
252  std::string full_robot_program_;
253 
256 
258 };
259 } // namespace urcl
260 #endif // ifndef UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED
uint32_t getControlFrequency() const
Definition: ur_driver.h:135
bool in_headless_mode_
Definition: ur_driver.h:251
This is the main class for interfacing the driver.
Definition: ur_driver.h:49
bool non_blocking_read_
Definition: ur_driver.h:255
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:166
comm::INotifier notifier_
Definition: ur_driver.h:237
VersionInformation robot_version_
Definition: ur_driver.h:257
std::string readScriptFile(const std::string &filename)
Definition: ur_driver.cpp:188
std::vector< std::string > getRTDEOutputRecipe()
Getter for the RTDE output recipe used in the RTDE client.
Definition: ur_driver.cpp:264
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)
Constructs a new UrDriver object. Upon initialization this class will check the calibration checksum ...
Definition: ur_driver.cpp:50
bool sendRobotProgram()
Sends the external control program to the robot.
Definition: ur_driver.cpp:251
uint32_t servoj_gain_
Definition: ur_driver.h:245
void startRTDECommunication()
Starts the RTDE communication.
Definition: ur_driver.cpp:177
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)
Constructs a new UrDriver object.
Definition: ur_driver.h:113
The RTDEWriter class offers an abstraction layer to send data to the robot via the RTDE interface...
Definition: rtde_writer.h:48
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:182
void checkCalibration(const std::string &checksum)
Checks if the kinematics information in the used model fits the actual robot.
Definition: ur_driver.cpp:196
std::unique_ptr< comm::ReverseInterface > reverse_interface_
Definition: ur_driver.h:239
const VersionInformation & getVersion()
Returns version information about the currently connected robot.
Definition: ur_driver.h:214
std::function< void(bool)> handle_program_state_
Definition: ur_driver.h:248
rtde_interface::RTDEWriter & getRTDEWriter()
Getter for the RTDE writer used to write to the robot&#39;s RTDE interface.
Definition: ur_driver.cpp:220
Parent class for notifiers.
Definition: pipeline.h:209
std::string full_robot_program_
Definition: ur_driver.h:252
bool writeKeepalive()
Write a keepalive signal only.
Definition: ur_driver.cpp:171
bool sendScript(const std::string &program)
Sends a custom script program to the robot.
Definition: ur_driver.cpp:225
std::unique_ptr< comm::URStream< primary_interface::PrimaryPackage > > primary_stream_
Definition: ur_driver.h:241
virtual ~UrDriver()=default
ControlMode
Control modes as interpreted from the script runnning on the robot.
Struct containing a robot&#39;s version information.
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:156
int get_packet_timeout_
Definition: ur_driver.h:254
std::unique_ptr< rtde_interface::RTDEClient > rtde_client_
Definition: ur_driver.h:238
int rtde_frequency_
Definition: ur_driver.h:236
double servoj_time_
Definition: ur_driver.h:244
double servoj_lookahead_time_
Definition: ur_driver.h:246
std::string robot_ip_
Definition: ur_driver.h:250
std::array< double, 6 > vector6d_t
Definition: types.h:30
std::unique_ptr< comm::URStream< primary_interface::PrimaryPackage > > secondary_stream_
Definition: ur_driver.h:242
std::unique_ptr< comm::ScriptSender > script_sender_
Definition: ur_driver.h:240
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:269


ur_client_library
Author(s): Thomas Timm Andersen, Simon Rasmussen, Felix Exner, Lea Steffen, Tristan Schnell
autogenerated on Sun May 9 2021 02:16:26