RMVL  2.1.0-dev
Robotic Manipulation and Vision Library
载入中...
搜索中...
未找到
rm::Client类 参考

OPC UA 客户端 更多...

#include <rmvl/opcua/client.hpp>

rm::Client 的协作图:

Public 成员函数

 Client (std::string_view address, const UserConfig &usr={})
 创建新的客户端对象,并建立连接
 
 ~Client ()
 
 Client (const Client &)=delete
 
 Client (Client &&)=default
 
Clientoperator= (const Client &)=delete
 
Clientoperator= (Client &&)=default
 
 operator ClientView () const
 
FindNodeInClient find (std::string_view browse_name, uint16_t ns=1U) const
 获取路径搜索必要信息
 
bool ok () const
 是否成功创建客户端并成功连接到服务器
 
void spin () const
 在网络上监听并处理到达的异步响应,同时进行内部维护、安全通道的更新和订阅管理
 
void spinOnce () const
 在网络上监听并处理到达的异步响应,同时进行内部维护、安全通道的更新和订阅管理
 
Variable read (const NodeId &node) const
 从指定的变量节点读数据
 
bool write (const NodeId &node, const Variable &val) const
 给指定的变量节点写数据
 
bool call (const NodeId &obj_node, const std::string &name, const std::vector< Variable > &inputs, std::vector< Variable > &outputs) const
 在客户端调用指定对象节点中的方法
 
bool call (const std::string &name, const std::vector< Variable > &inputs, std::vector< Variable > &outputs) const
 在客户端调用 ObjectsFolder 中的方法
 
NodeId addViewNode (const View &view) const
 添加 OPC UA 视图节点 ViewNode 至 ViewsFolder
 
bool monitor (NodeId node, DataChangeNotificationCallback on_change, uint32_t queue_size=10)
 创建变量节点监视项,以实现订阅节点的功能
 
bool monitor (NodeId node, const std::vector< std::string > &names, EventNotificationCallback on_event)
 创建事件监视项,以实现事件的订阅功能
 
bool remove (NodeId node)
 移除监视项
 

详细描述

OPC UA 客户端

示例
samples/opcua/opcua_client.cpp.

构造及析构函数说明

◆ Client() [1/3]

rm::Client::Client ( std::string_view address,
const UserConfig & usr = {} )

创建新的客户端对象,并建立连接

参数
[in]address连接地址,形如 opc.tcp://127.0.0.1:4840
[in]usr用户信息

◆ ~Client()

rm::Client::~Client ( )

◆ Client() [2/3]

rm::Client::Client ( const Client & )
delete

◆ Client() [3/3]

rm::Client::Client ( Client && )
default

成员函数说明

◆ addViewNode()

NodeId rm::Client::addViewNode ( const View & view) const

添加 OPC UA 视图节点 ViewNode 至 ViewsFolder

参数
[in]viewrm::View 表示的视图
返回
添加至服务器后,对应视图节点的唯一标识 NodeId

◆ call() [1/2]

bool rm::Client::call ( const NodeId & obj_node,
const std::string & name,
const std::vector< Variable > & inputs,
std::vector< Variable > & outputs ) const

在客户端调用指定对象节点中的方法

参数
[in]obj_node对象节点
[in]name方法名
[in]inputs输入参数列表
[out]outputs输出参数列表
返回
是否成功完成当前操作
示例
samples/opcua/opcua_client.cpp.

◆ call() [2/2]

bool rm::Client::call ( const std::string & name,
const std::vector< Variable > & inputs,
std::vector< Variable > & outputs ) const
inline

在客户端调用 ObjectsFolder 中的方法

参数
[in]name方法名 browse_name
[in]inputs输入参数列表
[out]outputs输出参数列表
返回
是否成功完成当前操作
函数调用图:

◆ find()

FindNodeInClient rm::Client::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] 元组
示例
samples/opcua/opcua_client.cpp.

◆ monitor() [1/2]

bool rm::Client::monitor ( NodeId node,
const std::vector< std::string > & names,
EventNotificationCallback on_event )

创建事件监视项,以实现事件的订阅功能

参数
[in]node待监视节点的 NodeId
[in]names关注的事件属性名列表,参考 Event::data()
[in]on_event事件回调函数
返回
事件监视创建成功?

◆ monitor() [2/2]

bool rm::Client::monitor ( NodeId node,
DataChangeNotificationCallback on_change,
uint32_t queue_size = 10 )

创建变量节点监视项,以实现订阅节点的功能

  • 服务器在设定的采样频率 opcua_param.SAMPLING_INTERVAL 下监视变量,若发生更改会尝试发出通知,通知的发送频率受到 opcua_param.PUBLISHING_INTERVAL 控制。当客户端收到通知时,执行 on_change 回调函数
  • 类似于 ROS 中的订阅话题,这里是订阅变量节点
参数
[in]node待监视节点的 NodeId
[in]on_change数据变更可调用对象
[in]queue_size通知存放的队列大小,若队列已满,新的通知会覆盖旧的通知,默认为 10
返回
变量节点监视创建成功?

◆ ok()

bool rm::Client::ok ( ) const
inline

是否成功创建客户端并成功连接到服务器

示例
samples/opcua/opcua_client.cpp.

◆ operator ClientView()

rm::Client::operator ClientView ( ) const
inline

◆ operator=() [1/2]

Client & rm::Client::operator= ( Client && )
default

◆ operator=() [2/2]

Client & rm::Client::operator= ( const Client & )
delete

◆ read()

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

从指定的变量节点读数据

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

◆ remove()

bool rm::Client::remove ( NodeId node)

移除监视项

参数
[in]node待移除监视项的节点号
返回
是否成功移除监视项

◆ spin()

void rm::Client::spin ( ) const

在网络上监听并处理到达的异步响应,同时进行内部维护、安全通道的更新和订阅管理

  • 执行事件循环,等效于 ROS/ROS2 工具包中的 ros::spin() 以及 rclcpp::spin()

◆ spinOnce()

void rm::Client::spinOnce ( ) const

在网络上监听并处理到达的异步响应,同时进行内部维护、安全通道的更新和订阅管理

  • 处理当前已到来的事件,等效于 ROS/ROS2 工具包中的 ros::spinOnce() 以及 rclcpp::spin_some()

◆ write()

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

给指定的变量节点写数据

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

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