client.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright (C) 2014-2014 by Sintef Raufoss Manufacturing *
3  * olivier.roulet@gmail.com *
4  * *
5  * This library is free software; you can redistribute it and/or modify *
6  * it under the terms of the GNU Lesser General Public License as *
7  * published by the Free Software Foundation; version 3 of the License. *
8  * *
9  * This library is distributed in the hope that it will be useful, *
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of *
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
12  * GNU Lesser General Public License for more details. *
13  * *
14  * You should have received a copy of the GNU Lesser General Public License *
15  * along with this library; if not, write to the *
16  * Free Software Foundation, Inc., *
17  * 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
18  ******************************************************************************/
19 
20 #include <opc/ua/client/client.h>
21 
22 #include <opc/common/uri_facade.h>
25 #include <opc/ua/node.h>
27 
28 #ifdef SSL_SUPPORT_MBEDTLS
29 #define MBEDTLS_X509_CRT_PARSE_C
30 #include <mbedtls/entropy.h>
31 #include <mbedtls/ctr_drbg.h>
32 #include <mbedtls/x509_crt.h>
33 #include <mbedtls/error.h>
34 #endif
35 
36 namespace OpcUa
37 {
38 
39 void KeepAliveThread::Start(Services::SharedPtr server, Node node, Duration period)
40 {
41  Server = server;
42  NodeToRead = node;
43  Period = period;
44  Running = true;
45  StopRequest = false;
46  Thread = std::thread([this] { this->Run(); });
47 }
48 
49 
51 {
52  LOG_INFO(Logger, "keep_alive_thread | starting");
53 
54  while (!StopRequest)
55  {
56  int64_t t_sleep = Period * 0.7;
57  LOG_DEBUG(Logger, "keep_alive_thread | sleeping for: {}ms", t_sleep);
58 
59  std::unique_lock<std::mutex> lock(Mutex);
60  std::cv_status status = Condition.wait_for(lock, std::chrono::milliseconds(t_sleep));
61 
62  if (status == std::cv_status::no_timeout)
63  {
64  break;
65  }
66 
67  LOG_DEBUG(Logger, "keep_alive_thread | renewing secure channel");
68 
70  params.ClientProtocolVersion = 0;
73  params.ClientNonce = std::vector<uint8_t>(1, 0);
74  params.RequestLifeTime = Period;
75  OpenSecureChannelResponse response = Server->OpenSecureChannel(params);
76 
78  {
80  }
81 
82  LOG_DEBUG(Logger, "keep_alive_thread | read a variable from address space to keep session open");
83 
85  }
86 
87  Running = false;
88 
89  LOG_INFO(Logger, "keep_alive_thread | stopped");
90 }
91 
93 {
94  if (!Running) { return; }
95 
96  LOG_DEBUG(Logger, "keep_alive_thread | stopping");
97 
98  StopRequest = true;
99  Condition.notify_all();
100 
101  try
102  {
103  Thread.join();
104  }
105 
106  catch (std::system_error & ex)
107  {
108  LOG_ERROR(Logger, "keep_alive_thread | exception thrown at attempt to join: {}", ex.what());
109 
110  throw ex;
111  }
112 }
113 
115  : KeepAlive(nullptr)
116 {
117  Logger = spdlog::get("UaClient");
118  if (!Logger)
119  {
120  Logger = spdlog::stderr_color_mt("UaClient");
121  }
122  if (debug)
123  {
124  Logger->set_level(spdlog::level::debug);
125  }
126  else
127  {
128  Logger->set_level(spdlog::level::info);
129  }
131 }
132 
133 std::vector<EndpointDescription> UaClient::GetServerEndpoints(const std::string & endpoint)
134 {
135  const Common::Uri serverUri(endpoint);
136  OpcUa::IOChannel::SharedPtr channel = OpcUa::Connect(serverUri.Host(), serverUri.Port(), Logger);
137 
139  params.EndpointUrl = endpoint;
140  params.SecurePolicy = "http://opcfoundation.org/UA/SecurityPolicy#None";
141 
142  Server = OpcUa::CreateBinaryClient(channel, params, Logger);
143 
145  std::vector<EndpointDescription> endpoints = UaClient::GetServerEndpoints();
147 
148  Server.reset(); //close channel
149 
150  return endpoints;
151 }
152 
153 std::vector<EndpointDescription> UaClient::GetServerEndpoints()
154 {
155  GetEndpointsParameters filter;
157  filter.ProfileUris.push_back("http://opcfoundation.org/UA-Profile/Transport/uatcp-uasc-uabinary");
158  filter.LocaleIds.push_back("http://opcfoundation.org/UA-Profile/Transport/uatcp-uasc-uabinary");
159  std::vector<EndpointDescription> endpoints = Server->Endpoints()->GetEndpoints(filter);
160 
161  return endpoints;
162 }
163 
165 {
166  std::vector<EndpointDescription> endpoints = GetServerEndpoints(endpoint);
167 
168  LOG_DEBUG(Logger, "ua_client | going through server endpoints and selected one we support");
169 
170  Common::Uri uri(endpoint);
171  bool has_login = !uri.User().empty();
172 
173  for (EndpointDescription ed : endpoints)
174  {
175  LOG_DEBUG(Logger, "ua_client | examining endpoint: {} with security: {}", ed.EndpointUrl, ed.SecurityPolicyUri);
176 
177  if (ed.SecurityPolicyUri == "http://opcfoundation.org/UA/SecurityPolicy#None")
178  {
179  LOG_DEBUG(Logger, "ua_client | security policy is OK, now looking at user token");
180 
181  if (ed.UserIdentityTokens.empty())
182  {
183  LOG_DEBUG(Logger, "ua_client | server does not use user token, OK");
184 
185  return ed;
186  }
187 
188  for (UserTokenPolicy token : ed.UserIdentityTokens)
189  {
190  if (has_login)
191  {
192  if (token.TokenType == UserTokenType::UserName)
193  {
194  LOG_DEBUG(Logger, "ua_client | endpoint selected");
195 
196  return ed;
197  }
198  }
199 
200  else if (token.TokenType == UserTokenType::Anonymous)
201  {
202  LOG_DEBUG(Logger, "ua_client | endpoint selected");
203 
204  return ed;
205  }
206  }
207  }
208  }
209 
210  throw std::runtime_error("No supported endpoints found on server");
211 }
212 
213 void UaClient::Connect(const std::string & endpoint)
214 {
215  EndpointDescription endpointdesc = SelectEndpoint(endpoint);
216  endpointdesc.EndpointUrl = endpoint; //force the use of the enpoint the user wants, seems like servers often send wrong hostname
217  Connect(endpointdesc);
218 }
219 
221 {
222  Endpoint = endpoint;
223  const Common::Uri serverUri(Endpoint.EndpointUrl);
224  OpcUa::IOChannel::SharedPtr channel = OpcUa::Connect(serverUri.Host(), serverUri.Port(), Logger);
225 
228  params.SecurePolicy = "http://opcfoundation.org/UA/SecurityPolicy#None";
229 
230  Server = OpcUa::CreateBinaryClient(channel, params, Logger);
231 
233 
234 
235  LOG_INFO(Logger, "ua_client | creating session ...");
236 
242  session.SessionName = SessionName;
243  session.EndpointUrl = endpoint.EndpointUrl;
244  session.Timeout = DefaultTimeout;
245  session.ServerURI = endpoint.Server.ApplicationUri;
246 
247  CreateSessionResponse createSessionResponse = Server->CreateSession(session);
248  CheckStatusCode(createSessionResponse.Header.ServiceResult);
249 
250  LOG_INFO(Logger, "ua_client | create session OK");
251 
252  LOG_INFO(Logger, "ua_client | activating session ...");
253 
254  ActivateSessionParameters sessionParameters;
255  {
256  //const SessionData &session_data = response.Session;
257  Common::Uri uri(session.EndpointUrl);
258  std::string user = uri.User();
259  std::string password = uri.Password();
260  bool user_identify_token_found = false;
261  sessionParameters.ClientSignature.Algorithm = "http://www.w3.org/2000/09/xmldsig#rsa-sha1";
262 
263  for (auto ep : createSessionResponse.Parameters.ServerEndpoints)
264  {
265  if (ep.SecurityMode == MessageSecurityMode::None)
266  {
267  for (auto token : ep.UserIdentityTokens)
268  {
269  if (user.empty())
270  {
271  if (token.TokenType == UserTokenType::Anonymous)
272  {
273  sessionParameters.UserIdentityToken.setPolicyId(token.PolicyId);
274  user_identify_token_found = true;
275  break;
276  }
277  }
278 
279  else
280  {
281  if (token.TokenType == UserTokenType::UserName)
282  {
283  sessionParameters.UserIdentityToken.setPolicyId(token.PolicyId);
284  sessionParameters.UserIdentityToken.setUser(user, password);
285 
286  if (token.SecurityPolicyUri != "http://opcfoundation.org/UA/SecurityPolicy#None")
287  {
288  EncryptPassword(sessionParameters.UserIdentityToken, createSessionResponse);
289  }
290 
291  user_identify_token_found = true;
292  break;
293  }
294  }
295  }
296  }
297  }
298 
299  if (!user_identify_token_found)
300  {
301  throw std::runtime_error("Cannot find suitable user identify token for session");
302  }
303  }
304  ActivateSessionResponse aresponse = Server->ActivateSession(sessionParameters);
306 
307  LOG_INFO(Logger, "ua_client | activate session OK");
308 
309  if (createSessionResponse.Parameters.RevisedSessionTimeout > 0 && createSessionResponse.Parameters.RevisedSessionTimeout < DefaultTimeout)
310  {
311  DefaultTimeout = createSessionResponse.Parameters.RevisedSessionTimeout;
312  }
313 
315 }
316 
318 {
319  OpenSecureChannelParameters channelparams;
320  channelparams.ClientProtocolVersion = 0;
322  channelparams.SecurityMode = MessageSecurityMode::None;
323  channelparams.ClientNonce = std::vector<uint8_t>(1, 0);
324  channelparams.RequestLifeTime = DefaultTimeout;
325  const OpenSecureChannelResponse & response = Server->OpenSecureChannel(channelparams);
326 
328 
330 
331  if (response.ChannelSecurityToken.RevisedLifetime > 0)
332  {
334  }
335 }
336 
338 {
339  Server->CloseSecureChannel(SecureChannelId);
340 }
341 
343 {
344  Disconnect();//Do not leave any thread or connection running
345 }
346 
348 {
349  KeepAlive.Stop();
350 
351  if (Server.get())
352  {
353  CloseSessionResponse response = Server->CloseSession();
354 
355  LOG_INFO(Logger, "ua_client | CloseSession response is {}", ToString(response.Header.ServiceResult));
356 
358  Server.reset();
359  }
360 
361 }
362 
364 {
365  KeepAlive.Stop();
366 
367  Server.reset(); //FIXME: check if we still need this
368 }
369 
370 std::vector<std::string> UaClient::GetServerNamespaces()
371 {
372  if (!Server) { throw std::runtime_error("Not connected");}
373 
375  return namespacearray.GetValue().As<std::vector<std::string>>();;
376 }
377 
379 {
380  if (!Server) { throw std::runtime_error("Not connected");}
381 
383  std::vector<std::string> uris = namespacearray.GetValue().As<std::vector<std::string>>();;
384 
385  for (uint32_t i = 0; i < uris.size(); ++i)
386  {
387  if (uris[i] == uri)
388  {
389  return i;
390  }
391  }
392 
393  throw std::runtime_error("Error namespace uri does not exists in server");
394  //return -1;
395 }
396 
397 
398 Node UaClient::GetNode(const std::string & nodeId) const
399 {
400  return Node(Server, ToNodeId(nodeId));
401 }
402 
403 Node UaClient::GetNode(const NodeId & nodeId) const
404 {
405  if (!Server) { throw std::runtime_error("Not connected");}
406 
407  return Node(Server, nodeId);
408 }
409 
411 {
412  if (!Server) { throw std::runtime_error("Not connected");}
413 
415 }
416 
418 {
419  if (!Server) { throw std::runtime_error("Not connected");}
420 
422 }
423 
425 {
426  if (!Server) { throw std::runtime_error("Not connected");}
427 
429 }
430 
431 void UaClient::DeleteNodes(std::vector<OpcUa::Node> & nodes, bool recursive)
432 {
433  if (recursive)
434  {
435  std::vector<OpcUa::Node> children = AddChilds(nodes);
436  nodes.insert(nodes.end(), children.begin(), children.end());
437  }
438 
439  LOG_DEBUG(Logger, "ua_client | deleting nodes ...");
440 
441  std::vector<OpcUa::DeleteNodesItem> nodesToDelete;
442  nodesToDelete.resize(nodes.size());
443 
444  for (unsigned i = 0; i < nodes.size(); i++)
445  {
446  nodesToDelete[i].NodeId = nodes[i].GetId();
447  nodesToDelete[i].DeleteTargetReferences = true;
448  }
449 
450  DeleteNodesResponse response = Server->DeleteNodes(nodesToDelete);
451 
452  for (std::vector<OpcUa::StatusCode>::iterator it = response.Results.begin(); it < response.Results.end(); it++)
453  {
454  CheckStatusCode(*it);
455  }
456 }
457 
458 std::vector<OpcUa::Node> UaClient::AddChilds(std::vector<OpcUa::Node> nodes)
459 {
460  std::vector<OpcUa::Node> results;
461  std::vector<OpcUa::Node> temp;
462 
463  for (std::vector<OpcUa::Node>::iterator it = nodes.begin(); it < nodes.end(); it++)
464  {
465  temp.clear();
466  temp = it->GetChildren();
467 
468  if (!temp.empty())
469  {
470  results.insert(results.begin(), temp.begin(), temp.end());
471  temp = AddChilds(temp);
472  results.insert(results.begin(), temp.begin(), temp.end());
473  }
474  }
475 
476  return results;
477 }
478 
479 Subscription::SharedPtr UaClient::CreateSubscription(unsigned int period, SubscriptionHandler & callback)
480 {
482  params.RequestedPublishingInterval = period;
483 
484  return std::make_shared<Subscription>(Server, params, callback, Logger);
485 }
486 
488 {
489  return ServerOperations(Server);
490 }
491 
493 {
494  if(response.Parameters.ServerCertificate.Data.empty() || response.Parameters.ServerNonce.Data.empty()) {
495  // server response does not contain information needed to encrypt password
496  return;
497  }
498 #ifdef SSL_SUPPORT_MBEDTLS
499  // use RSA-OAEP encryption if server certificate and nounce is provided
500  LOG_DEBUG(Logger, "ua_client | encrypting password RSA-OAEP");
501  auto error2string = [](int err_no) -> std::string
502  {
503  auto int_to_hex = [](u_int16_t i) -> std::string
504  {
505  std::stringstream stream;
506  stream << std::setfill ('0') << std::setw(sizeof(i)*2) << std::hex << i;
507  return stream.str();
508  };
509 
510  char buff[1024];
511  mbedtls_strerror(err_no, buff, sizeof(buff));
512  return "-" + int_to_hex(-err_no) + ": " + std::string(buff);
513  };
514  auto hex = [](const std::vector<unsigned char> &bytes)
515  {
516  std::string ret;
517  for(unsigned char c : bytes) {
518  auto val_to_digit = [](unsigned char c) { return (c >= 10)? c-10+'a': c+'0'; };
519  ret.push_back(val_to_digit(c/16));
520  ret.push_back(val_to_digit(c%16));
521  }
522  return ret;
523  };
524  mbedtls_x509_crt x509;
525  mbedtls_x509_crt_init( &x509 );
526  LOG_DEBUG(Logger, "ua_client | loading server certificate ... {}", hex(response.Parameters.ServerCertificate.Data));
527  int ret = mbedtls_x509_crt_parse_der( &x509, response.Parameters.ServerCertificate.Data.data(), response.Parameters.ServerCertificate.Data.size());
528  if( ret != 0 ) {
529  LOG_ERROR(Logger, "ua_client | error loading server certificate {}", error2string(ret) );
530  goto exit1;
531  }
532  {
533  mbedtls_entropy_context entropy;
534  mbedtls_ctr_drbg_context ctr_drbg;
535  const char pers[] = "freeopcua_ua_client";
536 
537  mbedtls_ctr_drbg_init( &ctr_drbg );
538  mbedtls_entropy_init( &entropy );
539 
540  LOG_DEBUG(Logger, "ua_client | seeding the random number generator...");
541  ret = mbedtls_ctr_drbg_seed( &ctr_drbg, mbedtls_entropy_func, &entropy, (const unsigned char *) pers, sizeof(pers) );
542  if( ret != 0 ) {
543  LOG_ERROR(Logger, "ua_client | error seeding the random number generator {}", error2string(ret) );
544  goto exit2;
545  }
546  {
547  mbedtls_rsa_context *rsa = mbedtls_pk_rsa(x509.pk);
548  rsa->padding = MBEDTLS_RSA_PKCS_V21;
549  rsa->hash_id = MBEDTLS_MD_SHA1;
550 
551  LOG_DEBUG(Logger, "ua_client | generating the RSA encrypted value...");
552 
553  unsigned char buff[rsa->len];
554  std::string input = identity.UserName.Password;
555  input += std::string(response.Parameters.ServerNonce.Data.begin(), response.Parameters.ServerNonce.Data.end());
556  {
557  std::string sn(4, '\0');
558  size_t l = input.length();
559  for (size_t i = 0; i < l; ++i) {
560  unsigned char n = l % 256;
561  l /= 256;
562  sn[i] = n;
563  }
564  input = sn + input;
565  }
566 
567  ret = mbedtls_rsa_pkcs1_encrypt( rsa, mbedtls_ctr_drbg_random, &ctr_drbg, MBEDTLS_RSA_PUBLIC, input.size(), (const unsigned char*)input.data(), buff );
568  if( ret != 0 ) {
569  LOG_ERROR(Logger, "ua_client | error RSA encryption {}", error2string(ret) );
570  goto exit2;
571  }
572  LOG_DEBUG(Logger, "ua_client | encrypted password: {}", hex(std::vector<unsigned char>(buff, buff + sizeof(buff))));
573 
574  identity.UserName.Password = std::string((const char*)buff, rsa->len);
575  identity.UserName.EncryptionAlgorithm = "http://www.w3.org/2001/04/xmlenc#rsa-oaep";
576  }
577 exit2:
578  mbedtls_ctr_drbg_free( &ctr_drbg );
579  mbedtls_entropy_free( &entropy );
580  }
581 exit1:
582  mbedtls_x509_crt_free( &x509 );
583 #endif
584 }
585 
586 } // namespace OpcUa
587 
std::condition_variable Condition
Definition: client.h:58
OpcUa::ByteString ServerNonce
std::string Password() const
Definition: uri_facade.h:36
OpcUa::ResponseHeader Header
Node GetNode(const NodeId &nodeid) const
Get a specific node by nodeid.
Definition: client.cpp:403
void CheckStatusCode(StatusCode code)
OpcUa Error codes. GNU LGPL.
void setUser(const std::string &user, const std::string &password)
virtual void EncryptPassword(OpcUa::UserIdentifyToken &identity, const CreateSessionResponse &response)
Definition: client.cpp:492
UaClient(bool debug=false)
create high level client this class is meant to be used to quickly/easily connect to an OPCUA server ...
Definition: client.cpp:114
ResponseHeader Header
Definition: session.h:36
void OpenSecureChannel()
Definition: client.cpp:317
ApplicationDescription ClientDescription
Definition: services.h:49
IntFormatSpec< int, TypeSpec<'x'> > hex(int value)
std::vector< OpcUa::EndpointDescription > ServerEndpoints
OpcUa::SignatureData ClientSignature
double Duration
Definition: datetime.h:53
Services::SharedPtr Server
Definition: client.h:54
OpcUa::ByteString ServerCertificate
#define LOG_ERROR(__logger__,...)
Definition: common/logger.h:27
StatusCode ServiceResult
Definition: types.h:259
void DeleteNodes(std::vector< OpcUa::Node > &nodes, bool recursive=false)
Definition: client.cpp:431
uint32_t SecureChannelId
Definition: client.h:173
#define LOG_DEBUG(__logger__,...)
Definition: common/logger.h:24
KeepAliveThread KeepAlive
Definition: client.h:172
std::vector< uint8_t > Data
Definition: types.h:37
std::string User() const
Definition: uri_facade.h:31
std::vector< EndpointDescription > GetServerEndpoints()
get endpoints from server, assume we are already connected
Definition: client.cpp:153
std::atomic< bool > Running
Definition: client.h:57
uint32_t DefaultTimeout
Definition: client.h:175
unsigned Port() const
Definition: uri_facade.h:46
void Disconnect()
Disconnect from server.
Definition: client.cpp:347
Node GetRootNode() const
helper methods for node you will probably want to access
Definition: client.cpp:410
OpcUa::CreateSessionResult Parameters
Node GetServerNode() const
Definition: client.cpp:424
std::shared_ptr< logger > get(const std::string &name)
Definition: spdlog_impl.h:40
OpcUa::ApplicationDescription Server
#define LOG_INFO(__logger__,...)
Definition: common/logger.h:25
void SetLogger(const Common::Logger::SharedPtr &logger)
Definition: client.h:48
void Connect(const std::string &endpoint)
connect to a server, specify endpoint as string
Definition: client.cpp:213
void Abort()
Abort server connection.
Definition: client.cpp:363
std::mutex Mutex
Definition: client.h:59
uint32_t GetNamespaceIndex(std::string uri)
Definition: client.cpp:378
Services::SharedPtr CreateBinaryClient(IOChannel::SharedPtr channel, const SecureConnectionParams &params, const Common::Logger::SharedPtr &logger=nullptr)
Create server based on opc ua binary protocol.
OpcUa::ApplicationType ApplicationType
std::string ApplicationUri
Definition: client.h:169
Moved from session.h.
Definition: types_manual.h:19
virtual ~UaClient()
Definition: client.cpp:342
Common::Logger::SharedPtr Logger
Definition: client.h:174
OPC UA Address space part. GNU LGPL.
ServerOperations CreateServerOperations()
Create a server operations object.
Definition: client.cpp:487
std::vector< std::string > GetServerNamespaces()
Get namespaces used by server.
Definition: client.cpp:370
Node GetObjectsNode() const
Definition: client.cpp:417
std::vector< uint8_t > ClientNonce
string uri
Definition: client.py:31
std::vector< OpcUa::Node > AddChilds(std::vector< OpcUa::Node > nodes)
Definition: client.cpp:458
std::string ProductUri
Definition: client.h:170
Variant GetValue() const
Definition: node.cpp:548
std::string SessionName
Definition: client.h:168
std::vector< std::string > LocaleIds
Subscription::SharedPtr CreateSubscription(unsigned int period, SubscriptionHandler &client)
Create a subscription objects.
Definition: client.cpp:479
OpcUa::LocalizedText ApplicationName
std::thread Thread
Definition: client.h:52
EndpointDescription Endpoint
Definition: client.h:166
A Node object represent an OPC-UA node. It is high level object intended for developper who want to e...
Definition: node.h:42
NodeId ToNodeId(const std::string &str, uint32_t defaultNamespace=0)
OpcUa::UserIdentifyToken UserIdentityToken
std::string ToString(const AttributeId &value)
OpcUa::UserTokenType TokenType
SecurityTokenRequestType RequestType
Services::SharedPtr Server
Definition: client.h:176
void Start(Services::SharedPtr server, Node node, Duration period)
Definition: client.cpp:39
std::atomic< bool > StopRequest
Definition: client.h:56
void CloseSecureChannel()
Definition: client.cpp:337
T As() const
Definition: variant.h:271
std::string Host() const
Definition: uri_facade.h:41
OpcUa::ResponseHeader Header
void setPolicyId(const std::string &id)
std::shared_ptr< logger > stderr_color_mt(const std::string &logger_name)
Definition: spdlog_impl.h:150
Common::Logger::SharedPtr Logger
Definition: client.h:60
std::unique_ptr< RemoteConnection > Connect(const std::string &host, unsigned port, const Common::Logger::SharedPtr &logger)
std::vector< std::string > ProfileUris
std::vector< OpcUa::StatusCode > Results
Definition: server.py:1
server
Definition: server.py:19
struct OpcUa::UserIdentifyToken::UserNameStruct UserName
EndpointDescription SelectEndpoint(const std::string &)
Connect to server and select one endpoint.
Definition: client.cpp:164


ros_opcua_impl_freeopcua
Author(s): Denis Štogl
autogenerated on Tue Jan 19 2021 03:06:04