RMVL  1.5.0-dev
Robotic Manipulation and Vision Library
载入中...
搜索中...
未找到

OPC UA 客户端视图 更多...

#include <rmvl/opcua/client.hpp>

rm::ClientView 的协作图:

Public 成员函数

 ClientView ()=default
 
 ClientView (UA_Client *client)
 创建不占有生命周期的 OPC UA 客户端视图,在 OPC UA 方法节点中使用特别有效
 
ClientViewoperator= (UA_Client *const client)
 
FindNodeInClient find (std::string_view browse_name, uint16_t ns=1U) const
 获取路径搜索必要信息
 
Variable read (const NodeId &node) const
 从指定的变量节点读数据
 
bool write (const NodeId &node, const Variable &val) const
 给指定的变量节点写数据
 

详细描述

OPC UA 客户端视图

构造及析构函数说明

◆ ClientView() [1/2]

rm::ClientView::ClientView ( )
default

◆ ClientView() [2/2]

rm::ClientView::ClientView ( UA_Client * client)
inline

创建不占有生命周期的 OPC UA 客户端视图,在 OPC UA 方法节点中使用特别有效

参数
[in]clientOPC UA 客户端指针

成员函数说明

◆ find()

FindNodeInClient rm::ClientView::find ( std::string_view browse_name,
uint16_t ns = 1U ) const
inline

获取路径搜索必要信息

需要配合管道运算符 | 完成路径搜索

auto dst_mode = src_node | clt.find("person") | clt.find("name");
参数
[in]browse_name浏览名
[in]ns命名空间索引,默认为 1
返回
目标节点信息
返回值
fnic[_client, browse_name] 元组

◆ operator=()

ClientView & rm::ClientView::operator= ( UA_Client *const client)
inline

◆ read()

Variable rm::ClientView::read ( const NodeId & node) const

从指定的变量节点读数据

参数
[in]node既存的变量节点的 NodeId
返回
读出的用 rm::Variable 表示的数据,未成功读取则返回空

◆ write()

bool rm::ClientView::write ( const NodeId & node,
const Variable & val ) const

给指定的变量节点写数据

参数
[in]node既存的变量节点的 NodeId
[in]val待写入的数据
返回
是否写入成功

该类的文档由以下文件生成: