ur_driver.cpp
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 //
18 // Many parts from this (Most of the URScript program) comes from the ur_modern_driver
19 // Copyright 2017, 2018 Simon Rasmussen (refactor)
20 // Copyright 2015, 2016 Thomas Timm Andersen (original version)
21 //
22 // -- END LICENSE BLOCK ------------------------------------------------
23 
24 //----------------------------------------------------------------------
31 //----------------------------------------------------------------------
32 
36 #include <memory>
37 #include <sstream>
38 
40 
41 namespace urcl
42 {
43 static const int32_t MULT_JOINTSTATE = 1000000;
44 static const std::string BEGIN_REPLACE("{{BEGIN_REPLACE}}");
45 static const std::string JOINT_STATE_REPLACE("{{JOINT_STATE_REPLACE}}");
46 static const std::string SERVO_J_REPLACE("{{SERVO_J_REPLACE}}");
47 static const std::string SERVER_IP_REPLACE("{{SERVER_IP_REPLACE}}");
48 static const std::string SERVER_PORT_REPLACE("{{SERVER_PORT_REPLACE}}");
49 
50 urcl::UrDriver::UrDriver(const std::string& robot_ip, const std::string& script_file,
51  const std::string& output_recipe_file, const std::string& input_recipe_file,
52  std::function<void(bool)> handle_program_state, bool headless_mode,
53  std::unique_ptr<ToolCommSetup> tool_comm_setup, const std::string& calibration_checksum,
54  const uint32_t reverse_port, const uint32_t script_sender_port, int servoj_gain,
55  double servoj_lookahead_time, bool non_blocking_read)
56  : servoj_time_(0.008)
57  , servoj_gain_(servoj_gain)
58  , servoj_lookahead_time_(servoj_lookahead_time)
59  , handle_program_state_(handle_program_state)
60  , robot_ip_(robot_ip)
61 {
62  URCL_LOG_DEBUG("Initializing urdriver");
63  URCL_LOG_DEBUG("Initializing RTDE client");
64  rtde_client_.reset(new rtde_interface::RTDEClient(robot_ip_, notifier_, output_recipe_file, input_recipe_file));
65 
66  primary_stream_.reset(
68  secondary_stream_.reset(
70  secondary_stream_->connect();
71  URCL_LOG_INFO("Checking if calibration data matches connected robot.");
72  checkCalibration(calibration_checksum);
73 
74  non_blocking_read_ = non_blocking_read;
76 
77  if (!rtde_client_->init())
78  {
79  throw UrException("Initialization of RTDE client went wrong.");
80  }
81 
82  rtde_frequency_ = rtde_client_->getMaxFrequency();
84 
85  std::string local_ip = rtde_client_->getIP();
86 
87  std::string prog = readScriptFile(script_file);
88  while (prog.find(JOINT_STATE_REPLACE) != std::string::npos)
89  {
90  prog.replace(prog.find(JOINT_STATE_REPLACE), JOINT_STATE_REPLACE.length(), std::to_string(MULT_JOINTSTATE));
91  }
92 
93  std::ostringstream out;
94  out << "lookahead_time=" << servoj_lookahead_time_ << ", gain=" << servoj_gain_;
95  while (prog.find(SERVO_J_REPLACE) != std::string::npos)
96  {
97  prog.replace(prog.find(SERVO_J_REPLACE), SERVO_J_REPLACE.length(), out.str());
98  }
99 
100  while (prog.find(SERVER_IP_REPLACE) != std::string::npos)
101  {
102  prog.replace(prog.find(SERVER_IP_REPLACE), SERVER_IP_REPLACE.length(), local_ip);
103  }
104 
105  while (prog.find(SERVER_PORT_REPLACE) != std::string::npos)
106  {
107  prog.replace(prog.find(SERVER_PORT_REPLACE), SERVER_PORT_REPLACE.length(), std::to_string(reverse_port));
108  }
109 
110  robot_version_ = rtde_client_->getVersion();
111 
112  std::stringstream begin_replace;
113  if (tool_comm_setup != nullptr)
114  {
115  if (robot_version_.major < 5)
116  {
117  throw ToolCommNotAvailable("Tool communication setup requested, but this robot version does not support using "
118  "the tool communication interface. Please check your configuration.",
119  5, robot_version_.major);
120  }
121  begin_replace << "set_tool_voltage("
122  << static_cast<std::underlying_type<ToolVoltage>::type>(tool_comm_setup->getToolVoltage()) << ")\n";
123  begin_replace << "set_tool_communication("
124  << "True"
125  << ", " << tool_comm_setup->getBaudRate() << ", "
126  << static_cast<std::underlying_type<Parity>::type>(tool_comm_setup->getParity()) << ", "
127  << tool_comm_setup->getStopBits() << ", " << tool_comm_setup->getRxIdleChars() << ", "
128  << tool_comm_setup->getTxIdleChars() << ")";
129  }
130  prog.replace(prog.find(BEGIN_REPLACE), BEGIN_REPLACE.length(), begin_replace.str());
131 
132  in_headless_mode_ = headless_mode;
133  if (in_headless_mode_)
134  {
135  full_robot_program_ = "def externalControl():\n";
136  std::istringstream prog_stream(prog);
137  std::string line;
138  while (std::getline(prog_stream, line))
139  {
140  full_robot_program_ += "\t" + line + "\n";
141  }
142  full_robot_program_ += "end\n";
144  }
145  else
146  {
147  script_sender_.reset(new comm::ScriptSender(script_sender_port, prog));
148  URCL_LOG_DEBUG("Created script sender");
149  }
150 
151  reverse_interface_.reset(new comm::ReverseInterface(reverse_port, handle_program_state));
152 
153  URCL_LOG_DEBUG("Initialization done");
154 }
155 
156 std::unique_ptr<rtde_interface::DataPackage> urcl::UrDriver::getDataPackage()
157 {
158  // This can take one of two values, 0ms or 100ms. The large timeout is for when the robot is commanding the control
159  // loop's timing (read is blocking). The zero timeout is for when the robot is sharing a control loop with
160  // something else (combined_robot_hw)
161  std::chrono::milliseconds timeout(get_packet_timeout_);
162 
163  return rtde_client_->getDataPackage(timeout);
164 }
165 
166 bool UrDriver::writeJointCommand(const vector6d_t& values, const comm::ControlMode control_mode)
167 {
168  return reverse_interface_->write(&values, control_mode);
169 }
170 
172 {
173  vector6d_t* fake = nullptr;
175 }
176 
178 {
179  rtde_client_->start();
180 }
181 
183 {
184  vector6d_t* fake = nullptr;
186 }
187 
188 std::string UrDriver::readScriptFile(const std::string& filename)
189 {
190  std::ifstream ifs(filename);
191  std::string content((std::istreambuf_iterator<char>(ifs)), (std::istreambuf_iterator<char>()));
192 
193  return content;
194 }
195 
196 void UrDriver::checkCalibration(const std::string& checksum)
197 {
198  if (primary_stream_ == nullptr)
199  {
200  throw std::runtime_error("checkCalibration() called without a primary interface connection being established.");
201  }
204  prod.setupProducer();
205 
206  CalibrationChecker consumer(checksum);
207 
208  comm::INotifier notifier;
209 
210  comm::Pipeline<primary_interface::PrimaryPackage> pipeline(prod, &consumer, "Pipeline", notifier);
211  pipeline.run();
212 
213  while (!consumer.isChecked())
214  {
215  std::this_thread::sleep_for(std::chrono::seconds(1));
216  }
217  URCL_LOG_DEBUG("Got calibration information from robot.");
218 }
219 
221 {
222  return rtde_client_->getWriter();
223 }
224 
225 bool UrDriver::sendScript(const std::string& program)
226 {
227  if (secondary_stream_ == nullptr)
228  {
229  throw std::runtime_error("Sending script to robot requested while there is no primary interface established. This "
230  "should not happen.");
231  }
232 
233  // urscripts (snippets) must end with a newline, or otherwise the controller's runtime will
234  // not execute them. To avoid problems, we always just append a newline here, even if
235  // there may already be one.
236  auto program_with_newline = program + '\n';
237 
238  size_t len = program_with_newline.size();
239  const uint8_t* data = reinterpret_cast<const uint8_t*>(program_with_newline.c_str());
240  size_t written;
241 
242  if (secondary_stream_->write(data, len, written))
243  {
244  URCL_LOG_DEBUG("Sent program to robot:\n%s", program_with_newline.c_str());
245  return true;
246  }
247  URCL_LOG_ERROR("Could not send program to robot");
248  return false;
249 }
250 
252 {
253  if (in_headless_mode_)
254  {
256  }
257  else
258  {
259  URCL_LOG_ERROR("Tried to send robot program directly while not in headless mode");
260  return false;
261  }
262 }
263 
264 std::vector<std::string> UrDriver::getRTDEOutputRecipe()
265 {
266  return rtde_client_->getOutputRecipe();
267 }
268 
269 void UrDriver::setKeepaliveCount(const uint32_t& count)
270 {
271  reverse_interface_->setKeepaliveCount(count);
272 }
273 } // namespace urcl
static const std::string SERVER_IP_REPLACE("{{SERVER_IP_REPLACE}}")
bool in_headless_mode_
Definition: ur_driver.h:251
#define URCL_LOG_ERROR(...)
Definition: log.h:37
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
void setupProducer() override
Triggers the stream to connect to the robot.
Definition: producer.h:63
void run()
Starts the producer and, if existing, the consumer in new threads.
Definition: pipeline.h:284
comm::INotifier notifier_
Definition: ur_driver.h:237
VersionInformation robot_version_
Definition: ur_driver.h:257
static const std::string JOINT_STATE_REPLACE("{{JOINT_STATE_REPLACE}}")
The stream is an abstraction of the TCPSocket that offers reading a full UR data package out of the s...
Definition: stream.h:42
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
The primary specific parser. Interprets a given byte stream as serialized primary packages and parses...
A specialized exception representing that communication to the tool is not possible.
Definition: exceptions.h:93
static const int32_t MULT_JOINTSTATE
Definition: ur_driver.cpp:43
uint32_t servoj_gain_
Definition: ur_driver.h:245
void startRTDECommunication()
Starts the RTDE communication.
Definition: ur_driver.cpp:177
Set when no controller is currently active controlling the robot.
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
rtde_interface::RTDEWriter & getRTDEWriter()
Getter for the RTDE writer used to write to the robot&#39;s RTDE interface.
Definition: ur_driver.cpp:220
static const std::string SERVO_J_REPLACE("{{SERVO_J_REPLACE}}")
Parent class for notifiers.
Definition: pipeline.h:209
uint32_t major
Major version number.
std::string full_robot_program_
Definition: ur_driver.h:252
#define URCL_LOG_DEBUG(...)
Definition: log.h:34
static const std::string SERVER_PORT_REPLACE("{{SERVER_PORT_REPLACE}}")
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
bool isChecked()
Used to make sure the calibration check is not performed several times.
ControlMode
Control modes as interpreted from the script runnning on the robot.
When this is set, the program is expected to stop and exit.
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
The CalibrationChecker class consumes primary packages ignoring all but KinematicsInfo packages...
The RTDEClient class manages communication over the RTDE interface. It contains the RTDE handshake an...
Definition: rtde_client.h:81
double servoj_time_
Definition: ur_driver.h:244
static const int UR_SECONDARY_PORT
double servoj_lookahead_time_
Definition: ur_driver.h:246
static const std::string BEGIN_REPLACE("{{BEGIN_REPLACE}}")
The ScriptSender class starts a TCPServer for a robot to connect to and waits for a request to receiv...
Definition: script_sender.h:45
std::string robot_ip_
Definition: ur_driver.h:250
The ReverseInterface class handles communication to the robot. It starts a server and waits for the r...
std::array< double, 6 > vector6d_t
Definition: types.h:30
The Pipepline manages the production and optionally consumption of packages. Cyclically the producer ...
Definition: pipeline.h:234
#define URCL_LOG_INFO(...)
Definition: log.h:36
std::unique_ptr< comm::URStream< primary_interface::PrimaryPackage > > secondary_stream_
Definition: ur_driver.h:242
A general producer for URPackages. Implements funcionality to produce packages by reading and parsing...
Definition: producer.h:40
std::unique_ptr< comm::ScriptSender > script_sender_
Definition: ur_driver.h:240
Our base class for exceptions. Specialized exceptions should inherit from those.
Definition: exceptions.h:40
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