opcua_client.cpp
Go to the documentation of this file.
1 
25 #include <ros/ros.h>
26 #include <signal.h>
27 
28 #include <opcua_helpers.h>
29 
30 #include "ros_opcua_msgs/Address.h"
31 #include "ros_opcua_msgs/TypeValue.h"
32 
33 #include "ros_opcua_srvs/CallMethod.h"
34 #include "ros_opcua_srvs/Connect.h"
35 #include "ros_opcua_srvs/Disconnect.h"
36 #include "ros_opcua_srvs/ListNode.h"
37 #include "ros_opcua_srvs/Read.h"
38 #include "ros_opcua_srvs/Subscribe.h"
39 #include "ros_opcua_srvs/Write.h"
40 #include "ros_opcua_srvs/Unsubscribe.h"
41 
42 #include <opc/ua/client/client.h>
43 #include <opc/ua/subscription.h>
44 
48 
49 std::map<std::string, std::shared_ptr<OpcUa::Subscription>> _subscriptions;
51 
52 std::map<std::string, ros::Publisher> _callback_publishers;
54 
55 std::map<std::string, uint32_t> _subscription_handles;
57 bool _connected = false;
58 
60 
64 {
72  void DataChange(uint32_t handle, const OpcUa::Node& node, const
73 OpcUa::Variant& value, OpcUa::AttributeId attr) override
74  {
75  ROS_DEBUG("Callback....");
77  }
78 };
79 
81 
83 
90 bool connect(ros_opcua_srvs::Connect::Request &req, ros_opcua_srvs::Connect::Response &res)
91 {
92  // TODO: set connect status
93 
94  ROS_DEBUG("Establishing connection to OPC-UA server on address: %s", req.endpoint.c_str());
95  try {
96  _client.Connect(req.endpoint);
97  ROS_INFO("Connection to OPC-UA server on address '%s' established!", req.endpoint.c_str());
98  res.success = true;
99  _connected = true;
100  }
101  catch (const std::exception& exc){
102  ROS_ERROR("OPC-UA client node %s: Connection to OPC-UA server on address %s failed! Message: %s", ros::this_node::getName().c_str(), req.endpoint.c_str(), exc.what());
103 
104  res.success = false;
105  std::stringstream ss;
106  ss << "Connection to OPC-UA server on address " << req.endpoint << " failed! Message: " << exc.what();
107  res.error_message = ss.str();
108  }
109  catch (...) {
110  ROS_ERROR("Connection to OPC-UA server on address %s failed with unknown exception", req.endpoint.c_str());
111  res.success = false;
112  res.error_message = "'Connect' service failed with Unknown exception";
113  }
114  return true;
115 }
116 
123 bool disconnect(ros_opcua_srvs::Disconnect::Request &req, ros_opcua_srvs::Disconnect::Response &res)
124 {
125  ROS_DEBUG("Disconnecting from OPC-UA server...");
126  try {
128  ROS_INFO("Disconnection succeded!");
129  _connected = false;
130  res.success = true;
131  }
132  catch (const std::exception& exc){
133  ROS_ERROR("OPC-UA client node %s: Disconnection failed! (maybe client was not connected before?). Message: %s", ros::this_node::getName().c_str(), exc.what());
134 
135  res.success = false;
136  res.error_message = "Disconect service failed with exception: ";
137  res.error_message.append(exc.what());
138  }
139  catch (...) {
140  ROS_ERROR("'Disconnect' service failed with unknown exception");
141  res.success = false;
142  res.error_message = "'Disconnect' service failed with unknown exception";
143  }
144  return true;
145 }
146 
153 bool list_node(ros_opcua_srvs::ListNode::Request &req, ros_opcua_srvs::ListNode::Response &res)
154 {
155  ROS_DEBUG("OPC-UA client node %s: 'ListNode' service called with node Id: %s parameters", ros::this_node::getName().c_str(), req.node.nodeId.c_str());
156 
157  OpcUa::Node node;
158  try {
159  if (req.node.nodeId == "") {
160  node = _client.GetObjectsNode();
161  }
162  else {
163  node = _client.GetNode(req.node.nodeId);
164  }
165 
166  for (OpcUa::Node child : node.GetChildren()){
167  ros_opcua_msgs::Address address;
168  address.nodeId = OpcUa::ToString(child.GetId());
169  address.qualifiedName = child.GetBrowseName().Name;
170  res.children.push_back(address);
171  }
172  res.success = true;
173  }
174  catch (const std::exception& exc){
175  ROS_ERROR("OPC-UA client node %s: 'ListNode' service called with node Id: %s, parameters failed! Exception: %s", ros::this_node::getName().c_str(), req.node.nodeId.c_str(), exc.what());
176 
177  res.success = false;
178  res.error_message = "ListNode service failed with exception: ";
179  res.error_message.append(exc.what());
180  }
181  catch (...)
182  {
183  ROS_ERROR("OPC-UA client node %s: 'ListNode' service called with node Id: %s parameters failed! Unknown exception!", ros::this_node::getName().c_str(), req.node.nodeId.c_str());
184 
185  res.success = false;
186  res.error_message = "ListNode service failed with Unknown exception";
187  }
188  return true;
189 }
190 
191 bool call_method(ros_opcua_srvs::CallMethod::Request &req, ros_opcua_srvs::CallMethod::Response &res)
192 {
193  ROS_DEBUG("OPC-UA client node %s: 'CallMethod' service called with node Id: %s and %s parameters", ros::this_node::getName().c_str(), req.node.nodeId.c_str(), req.method.nodeId.c_str());
194 
195  try {
196  OpcUa::Node node = _client.GetNode(req.node.nodeId);
197  OpcUa::NodeId method_id = OpcUa::ToNodeId(req.method.nodeId);
198  std::vector<OpcUa::Variant> inputArguments;
199 
200  for (ros_opcua_msgs::TypeValue typeValue : req.data) {
201  std::cout << "Variant: " <<
202 convertTypeValueToVariant(typeValue).ToString() << std::endl;
203  inputArguments.push_back(convertTypeValueToVariant(typeValue));
204  }
205 
206  std::vector<OpcUa::Variant> outputArguments = node.CallMethod(method_id, inputArguments);
207 
208  for (OpcUa::Variant variant : outputArguments) {
209  res.data.push_back(convertVariantToTypeValue(variant));
210  }
211 
212  res.success = true;
213 
214  }
215  catch (const std::exception& exc){
216  ROS_ERROR("OPC-UA client node %s: 'CallMethod' service called with node Id: %s and %s parameters failed! Exception: %s", ros::this_node::getName().c_str(), req.node.nodeId.c_str(), req.method.nodeId.c_str(), exc.what());
217 
218  res.success = false;
219  res.error_message = "Call method service failed with exception: ";
220  res.error_message.append(exc.what());
221  }
222  catch (...)
223  {
224  ROS_ERROR("OPC-UA client node %s: 'CallMethod' service called with node Id: %s parameters failed! Unknown exception!", ros::this_node::getName().c_str(), req.node.nodeId.c_str());
225 
226  res.success = false;
227  res.error_message = "Call method service failed with Unknown exception";
228  }
229  return true;
230 }
231 
238 bool read(ros_opcua_srvs::Read::Request &req, ros_opcua_srvs::Read::Response &res)
239 {
240  ROS_DEBUG("OPC-UA client node %s: 'Read' service called with node Id: %s parameters", ros::this_node::getName().c_str(), req.node.nodeId.c_str());
241 
242  try {
243  OpcUa::Node variable = _client.GetNode(req.node.nodeId);
244 
245  res.success = true;
246  res.data = convertVariantToTypeValue(variable.GetValue());
247 
248  if (res.data.type == "Unknown") {
249  res.success = false;
250  res.error_message = "Unknown data type!!";
251  ROS_DEBUG("Reading failed!");
252  }
253  }
254  catch (const std::exception& exc){
255  ROS_ERROR("OPC-UA client node %s: 'Read' service called with node Id: %s, parameters failed! Exception: %s", ros::this_node::getName().c_str(), req.node.nodeId.c_str(), exc.what());
256 
257  res.success = false;
258  res.error_message = "Read service failed with exception: ";
259  res.error_message.append(exc.what());
260  }
261  catch (...)
262  {
263  ROS_ERROR("OPC-UA client node %s: 'Read' service called with node Id: %s parameters failed! Unknown exception!", ros::this_node::getName().c_str(), req.node.nodeId.c_str());
264 
265  res.success = false;
266  res.error_message = "Read service failed with Unknown exception";
267  }
268  return true;
269 }
270 
277 bool write(ros_opcua_srvs::Write::Request &req, ros_opcua_srvs::Write::Response &res)
278 {
279  ROS_DEBUG("OPC-UA client node %s: 'Write' service called with node Id: %s, parameters", ros::this_node::getName().c_str(), req.node.nodeId.c_str());
280 
281  try {
282  OpcUa::Node variable = _client.GetNode(req.node.nodeId);
283 
284  OpcUa::Variant variant = convertTypeValueToVariant(req.data);
285 
286  if (!variant.IsNul()) {
287 // if (variant.Type() == OpcUa::VariantType::STRING) {
288 // if (((std::string)variant).length() == 0) {
289 // variant = std::string(" ");
290 // }
291 // }
292  variable.SetValue(variant);
293  res.success = true;
294  }
295  else {
296  res.success = false;
297  res.error_message = "Unknown data type: ";
298  res.error_message.append(req.data.type);
299  ROS_DEBUG("Writing failed!");
300  }
301  }
302  catch (const std::exception& exc){
303  ROS_ERROR("OPC-UA client node %s: 'Write' service called with node Id: %s, type: '%s' parameters failed! Exception: %s", ros::this_node::getName().c_str(), req.node.nodeId.c_str(), req.data.type.c_str(), exc.what());
304 
305  res.success = false;
306  res.error_message = "Write service failed with exception: ";
307  res.error_message.append(exc.what());
308  }
309  catch (...)
310  {
311  ROS_ERROR("OPC-UA client node %s: 'Write' service called with node Id: %s, type: '%s' parameters failed! Unknown exception!", ros::this_node::getName().c_str(), req.node.nodeId.c_str(), req.data.type.c_str());
312 
313  res.success = false;
314  res.error_message = "Write service failed with Unknown exception";
315  }
316 
317  return true;
318 }
319 
327 bool subscribe(ros_opcua_srvs::Subscribe::Request &req, ros_opcua_srvs::Subscribe::Response &res)
328 {
329  ROS_DEBUG("OPC-UA client node %s: 'Subscribe' service called with node Id: %s parameters", ros::this_node::getName().c_str(), req.node.nodeId.c_str());
330 
331  try {
332  // TODO: Check if already subscribed to node
333 
334  OpcUa::Node variable = _client.GetNode(req.node.nodeId);
335  std::string node_string = OpcUa::ToString(variable.GetId());
336 
337  ros::NodeHandle nodeHandle("~");
338  _callback_publishers[node_string] = nodeHandle.advertise<ros_opcua_msgs::TypeValue>(req.callback_topic, 1);
339 
340  _subscriptions[node_string] = _client.CreateSubscription(100, _sclt);
341  _subscription_handles[node_string] = _subscriptions[node_string]->SubscribeDataChange(variable);
342 
343  ROS_INFO("Node successfully subscribed!");
344  res.success = true;
345  }
346  catch (const std::exception& exc){
347  ROS_ERROR("OPC-UA client node %s: 'Subscribe' service called with node Id: %s parameters failed!", ros::this_node::getName().c_str(), req.node.nodeId.c_str());
348 
349  res.success = false;
350  res.error_message = "Subscribe service failed with exception: ";
351  res.error_message.append(exc.what());
352  }
353  catch (...)
354  {
355  ROS_ERROR("OPC-UA client node %s: 'Subscribe' service called with node Id: %s parameters failed!", ros::this_node::getName().c_str(), req.node.nodeId.c_str());
356 
357  res.success = false;
358  res.error_message = "Subscribe service failed with Unknown exception";
359  }
360 
361  return true;
362 }
363 
370 bool unsubscribe(ros_opcua_srvs::Unsubscribe::Request &req, ros_opcua_srvs::Unsubscribe::Response &res)
371 {
372  ROS_DEBUG("OPC-UA client node %s: 'Unsubscribe' service called with node Id: %s parameters", ros::this_node::getName().c_str(), req.node.nodeId.c_str());
373 
374  try {
375  // TODO: Check if already subscribed to node
376 
377  // TODO: Why is here return status false even the subscription was ok?
378 
379  OpcUa::Node variable = _client.GetNode(req.node.nodeId);
380  std::string node_string = OpcUa::ToString(variable.GetId());
381 
382  _subscriptions[node_string]->UnSubscribe(_subscription_handles[node_string]);
383  _callback_publishers[node_string].shutdown();
384 
385  _subscriptions.erase(node_string);
386  _subscription_handles.erase(node_string);
387  _callback_publishers.erase(node_string);
388 
389  ROS_INFO("Node successfully unsubscribed!");
390  res.success = true;
391  }
392  catch (const std::exception& exc){
393  ROS_ERROR("OPC-UA client node %s: 'Unsubscribe' service called with node Id: %s parameters failed!", ros::this_node::getName().c_str(), req.node.nodeId.c_str());
394 
395  res.success = false;
396  res.error_message = "Unsubscribe service failed with exception: ";
397  res.error_message.append(exc.what());
398  }
399  catch (...)
400  {
401  ROS_ERROR("OPC-UA client node %s: 'Unsubscribe' service called with node Id: %s parameters failed!", ros::this_node::getName().c_str(), req.node.nodeId.c_str());
402 
403  res.success = false;
404  res.error_message = "Unsubscribe service failed with Unknown exception";
405  }
406 
407  return true;
408 }
409 
413 void on_shutdown(int sig)
414 {
416 
417  ros::shutdown();
418 }
419 
426 int main (int argc, char** argv)
427 {
428  ros::init(argc, argv, "opcua_client_node");
429  ros::NodeHandle nodeHandle("~");
430  signal(SIGINT, on_shutdown);
431 
432  ros::ServiceServer connect_service = nodeHandle.advertiseService("connect", connect);
433  ROS_DEBUG("OPC-UA client node %s: 'Connect' service available on on: %s", ros::this_node::getName().c_str(), connect_service.getService().c_str());
434  ros::ServiceServer disconnect_service = nodeHandle.advertiseService("disconnect", disconnect);
435  ROS_DEBUG("OPC-UA client node %s: 'Disconnect' service available on: %s", ros::this_node::getName().c_str(), disconnect_service.getService().c_str());
436 
437  // List node
438  ros::ServiceServer list_node_service = nodeHandle.advertiseService("list_node", list_node);
439  ROS_DEBUG("OPC-UA client node %s: 'ListNode' service available on on: %s", ros::this_node::getName().c_str(), connect_service.getService().c_str());
440 
441  // Method Call
442  ros::ServiceServer call_method_service = nodeHandle.advertiseService("call_method", call_method);
443  ROS_DEBUG("OPC-UA client node %s: 'CallMethod' service available on: %s", ros::this_node::getName().c_str(), call_method_service.getService().c_str());
444 
445  // Reading of data
446  ros::ServiceServer read_service = nodeHandle.advertiseService("read", read);
447  ROS_DEBUG("OPC-UA client node %s: 'Read' service available on: %s", ros::this_node::getName().c_str(), read_service.getService().c_str());
448 
449  // Writing of data
450  ros::ServiceServer write_service = nodeHandle.advertiseService("write", write);
451  ROS_DEBUG("OPC-UA client node %s: 'Write' service available on: %s", ros::this_node::getName().c_str(), write_service.getService().c_str());
452 
453  // Subscriptions
454  ros::ServiceServer subscribe_service = nodeHandle.advertiseService("subscribe", subscribe);
455  ROS_DEBUG("OPC-UA client node %s: 'Subscribe' service available on: %s", ros::this_node::getName().c_str(), subscribe_service.getService().c_str());
456  ros::ServiceServer unsubscribe_service = nodeHandle.advertiseService("unsubscribe", unsubscribe);
457  ROS_DEBUG("OPC-UA client node %s: 'Unsubscribe' service available on: %s", ros::this_node::getName().c_str(), unsubscribe_service.getService().c_str());
458 
459 
460  ROS_INFO("OPCUA client node: %s is ready!", ros::this_node::getName().c_str());
461 
462  ros::spin();
463 
464  return 0;
465 }
SubClient _sclt
Subscription client store.
Node GetNode(const NodeId &nodeid) const
Get a specific node by nodeid.
Definition: client.cpp:403
bool disconnect(ros_opcua_srvs::Disconnect::Request &req, ros_opcua_srvs::Disconnect::Response &res)
bool subscribe(ros_opcua_srvs::Subscribe::Request &req, ros_opcua_srvs::Subscribe::Response &res)
int main(int argc, char **argv)
bool IsNul() const
bool connect(ros_opcua_srvs::Connect::Request &req, ros_opcua_srvs::Connect::Response &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Subscription client class handles subscription callbacks.
ROSCPP_DECL const std::string & getName()
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void Disconnect()
Disconnect from server.
Definition: client.cpp:347
bool write(ros_opcua_srvs::Write::Request &req, ros_opcua_srvs::Write::Response &res)
NodeId GetId() const
Definition: node.cpp:50
bool unsubscribe(ros_opcua_srvs::Unsubscribe::Request &req, ros_opcua_srvs::Unsubscribe::Response &res)
std::map< std::string, ros::Publisher > _callback_publishers
Callback publishers list.
void Connect(const std::string &endpoint)
connect to a server, specify endpoint as string
Definition: client.cpp:213
#define ROS_INFO(...)
handle
Definition: client.py:58
bool list_node(ros_opcua_srvs::ListNode::Request &req, ros_opcua_srvs::ListNode::Response &res)
std::string getService() const
bool read(ros_opcua_srvs::Read::Request &req, ros_opcua_srvs::Read::Response &res)
ROSCPP_DECL void spin()
Node GetObjectsNode() const
Definition: client.cpp:417
Variant GetValue() const
Definition: node.cpp:548
std::vector< Variant > CallMethod(NodeId methodId, std::vector< Variant > inputArguments) const
Definition: node.cpp:80
Subscription::SharedPtr CreateSubscription(unsigned int period, SubscriptionHandler &client)
Create a subscription objects.
Definition: client.cpp:479
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)
void DataChange(uint32_t handle, const OpcUa::Node &node, const OpcUa::Variant &value, OpcUa::AttributeId attr) override
ros_opcua_msgs::TypeValue convertVariantToTypeValue(const OpcUa::Variant &variant)
std::string ToString(const AttributeId &value)
bool _connected
Connected status variable.
void SetValue(const Variant &val) const
Definition: node.cpp:135
ROSCPP_DECL void shutdown()
std::map< std::string, uint32_t > _subscription_handles
List of subscription handles.
bool call_method(ros_opcua_srvs::CallMethod::Request &req, ros_opcua_srvs::CallMethod::Response &res)
OpcUa::Variant convertTypeValueToVariant(ros_opcua_msgs::TypeValue &typeValue)
std::map< std::string, std::shared_ptr< OpcUa::Subscription > > _subscriptions
Subscription list.
#define ROS_ERROR(...)
OpcUa::UaClient _client(false)
Client variable.
This file contains helper functions for ROS implementation of OpcUa client.
void on_shutdown(int sig)
#define ROS_DEBUG(...)
std::string ToString() const


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