Loading include/opcua_bridge/node.hpp +2 −0 Original line number Diff line number Diff line Loading @@ -25,6 +25,8 @@ namespace obridge { ornl::ros::util::CapturedLogger m_logger; opcua::Client m_client; std::map<std::string, rclcpp::PublisherBase::SharedPtr> m_publishers; }; } include/opcua_bridge/types.hpp 0 → 100644 +58 −0 Original line number Diff line number Diff line #pragma once // rclcpp #include <rclcpp/rclcpp.hpp> #include <std_msgs/msg/bool.hpp> #include <std_msgs/msg/float32.hpp> #include <std_msgs/msg/string.hpp> template<> struct rclcpp::TypeAdapter<std::string, std_msgs::msg::String> { using is_specialized = std::true_type; using custom_type = std::string; using ros_message_type = std_msgs::msg::String; static void convert_to_ros_message(const custom_type& source, ros_message_type& destination) { destination.data = source; } static void convert_to_custom(const ros_message_type & source, custom_type & destination) { destination = source.data; } }; RCLCPP_USING_CUSTOM_TYPE_AS_ROS_MESSAGE_TYPE(std::string, std_msgs::msg::String); template<> struct rclcpp::TypeAdapter<float, std_msgs::msg::Float32> { using is_specialized = std::true_type; using custom_type = float; using ros_message_type = std_msgs::msg::Float32; static void convert_to_ros_message(const custom_type& source, ros_message_type& destination) { destination.data = source; } static void convert_to_custom(const ros_message_type & source, custom_type & destination) { destination = source.data; } }; RCLCPP_USING_CUSTOM_TYPE_AS_ROS_MESSAGE_TYPE(float, std_msgs::msg::Float32); template<> struct rclcpp::TypeAdapter<bool, std_msgs::msg::Bool> { using is_specialized = std::true_type; using custom_type = bool; using ros_message_type = std_msgs::msg::Bool; static void convert_to_ros_message(const custom_type& source, ros_message_type& destination) { destination.data = source; } static void convert_to_custom(const ros_message_type & source, custom_type & destination) { destination = source.data; } }; RCLCPP_USING_CUSTOM_TYPE_AS_ROS_MESSAGE_TYPE(bool, std_msgs::msg::Bool); src/node.cpp +56 −5 Original line number Diff line number Diff line Loading @@ -4,7 +4,10 @@ #include "oru/rclcpp/log.hpp" // open62541pp #include <open62541pp/subscription.hpp> #include <open62541pp/node.hpp> // local #include "opcua_bridge/types.hpp" using namespace std::chrono_literals; Loading @@ -13,14 +16,17 @@ namespace obridge { Node("opcua_bridge", options), m_logger(this->get_logger()) { this->declare_parameter("server.host", "0.0.0.0"); this->declare_parameter("server.host", "fronius.1500mx.mdf.internal"); this->declare_parameter("server.port", "4840"); this->declare_parameter("topics", std::vector<std::string> { }); this->declare_parameter("bridge.namespace", 1); this->declare_parameter("bridge.poll", 200); //this->declare_parameter("bridge.objects", std::vector<std::string> { }); this->attach(); m_timer = this->create_wall_timer(1000ms, std::bind(&OpcuaNode::attach, this)); int freq = this->get_parameter("bridge.poll").as_int(); m_timer = this->create_wall_timer(std::chrono::milliseconds(freq), std::bind(&OpcuaNode::poll, this)); m_logger.info("opcua bridge now available"); }; Loading @@ -46,7 +52,52 @@ namespace obridge { } auto OpcuaNode::poll() -> void { this->attach(); int space = this->get_parameter("bridge.namespace").as_int(); auto read_value = [&]<typename value_t>(int space, std::string object) -> void { opcua::Node node = { m_client, opcua::NodeId { static_cast<opcua::NamespaceIndex>(space), object } }; value_t value = node.readValue().to<value_t>(); m_logger.debug("{}:{} - {}", space, object, value); if (!m_publishers.contains(object)) { m_publishers[object] = this->create_publisher<value_t>( fmt::format("opcua/{}", object), rclcpp::QoS(10) ); } rclcpp::PublisherBase::SharedPtr pubBase = m_publishers[object]; auto pub = std::static_pointer_cast<rclcpp::Publisher<value_t>>(pubBase); pub->publish(value); }; read_value.template operator()<float>(space, "ACTUAL_CURRENT"); read_value.template operator()<float>(space, "ACTUAL_GASFLOW"); read_value.template operator()<float>(space, "ACTUAL_POWER"); read_value.template operator()<float>(space, "ACTUAL_VOLTAGE"); read_value.template operator()<float>(space, "ACTUAL_WELDINGTIME"); read_value.template operator()<float>(space, "ACTUAL_WFS"); read_value.template operator()<float>(space, "DISPLAY_CURRENT"); read_value.template operator()<float>(space, "DISPLAY_ENERGY"); read_value.template operator()<float>(space, "DISPLAY_POWER"); read_value.template operator()<float>(space, "DISPLAY_VOLTAGE"); read_value.template operator()<float>(space, "DISPLAY_WFS"); read_value.template operator()<float>(space, "WIREBUFFER_VALUE"); read_value.template operator()<float>(space, "ERROR"); read_value.template operator()<bool>(space, "PROCESS_ACTIVE"); read_value.template operator()<std::string>(space, "FIRMWAREVERSION"); read_value.template operator()<std::string>(space, "SERIALNUMBER"); } } Loading Loading
include/opcua_bridge/node.hpp +2 −0 Original line number Diff line number Diff line Loading @@ -25,6 +25,8 @@ namespace obridge { ornl::ros::util::CapturedLogger m_logger; opcua::Client m_client; std::map<std::string, rclcpp::PublisherBase::SharedPtr> m_publishers; }; }
include/opcua_bridge/types.hpp 0 → 100644 +58 −0 Original line number Diff line number Diff line #pragma once // rclcpp #include <rclcpp/rclcpp.hpp> #include <std_msgs/msg/bool.hpp> #include <std_msgs/msg/float32.hpp> #include <std_msgs/msg/string.hpp> template<> struct rclcpp::TypeAdapter<std::string, std_msgs::msg::String> { using is_specialized = std::true_type; using custom_type = std::string; using ros_message_type = std_msgs::msg::String; static void convert_to_ros_message(const custom_type& source, ros_message_type& destination) { destination.data = source; } static void convert_to_custom(const ros_message_type & source, custom_type & destination) { destination = source.data; } }; RCLCPP_USING_CUSTOM_TYPE_AS_ROS_MESSAGE_TYPE(std::string, std_msgs::msg::String); template<> struct rclcpp::TypeAdapter<float, std_msgs::msg::Float32> { using is_specialized = std::true_type; using custom_type = float; using ros_message_type = std_msgs::msg::Float32; static void convert_to_ros_message(const custom_type& source, ros_message_type& destination) { destination.data = source; } static void convert_to_custom(const ros_message_type & source, custom_type & destination) { destination = source.data; } }; RCLCPP_USING_CUSTOM_TYPE_AS_ROS_MESSAGE_TYPE(float, std_msgs::msg::Float32); template<> struct rclcpp::TypeAdapter<bool, std_msgs::msg::Bool> { using is_specialized = std::true_type; using custom_type = bool; using ros_message_type = std_msgs::msg::Bool; static void convert_to_ros_message(const custom_type& source, ros_message_type& destination) { destination.data = source; } static void convert_to_custom(const ros_message_type & source, custom_type & destination) { destination = source.data; } }; RCLCPP_USING_CUSTOM_TYPE_AS_ROS_MESSAGE_TYPE(bool, std_msgs::msg::Bool);
src/node.cpp +56 −5 Original line number Diff line number Diff line Loading @@ -4,7 +4,10 @@ #include "oru/rclcpp/log.hpp" // open62541pp #include <open62541pp/subscription.hpp> #include <open62541pp/node.hpp> // local #include "opcua_bridge/types.hpp" using namespace std::chrono_literals; Loading @@ -13,14 +16,17 @@ namespace obridge { Node("opcua_bridge", options), m_logger(this->get_logger()) { this->declare_parameter("server.host", "0.0.0.0"); this->declare_parameter("server.host", "fronius.1500mx.mdf.internal"); this->declare_parameter("server.port", "4840"); this->declare_parameter("topics", std::vector<std::string> { }); this->declare_parameter("bridge.namespace", 1); this->declare_parameter("bridge.poll", 200); //this->declare_parameter("bridge.objects", std::vector<std::string> { }); this->attach(); m_timer = this->create_wall_timer(1000ms, std::bind(&OpcuaNode::attach, this)); int freq = this->get_parameter("bridge.poll").as_int(); m_timer = this->create_wall_timer(std::chrono::milliseconds(freq), std::bind(&OpcuaNode::poll, this)); m_logger.info("opcua bridge now available"); }; Loading @@ -46,7 +52,52 @@ namespace obridge { } auto OpcuaNode::poll() -> void { this->attach(); int space = this->get_parameter("bridge.namespace").as_int(); auto read_value = [&]<typename value_t>(int space, std::string object) -> void { opcua::Node node = { m_client, opcua::NodeId { static_cast<opcua::NamespaceIndex>(space), object } }; value_t value = node.readValue().to<value_t>(); m_logger.debug("{}:{} - {}", space, object, value); if (!m_publishers.contains(object)) { m_publishers[object] = this->create_publisher<value_t>( fmt::format("opcua/{}", object), rclcpp::QoS(10) ); } rclcpp::PublisherBase::SharedPtr pubBase = m_publishers[object]; auto pub = std::static_pointer_cast<rclcpp::Publisher<value_t>>(pubBase); pub->publish(value); }; read_value.template operator()<float>(space, "ACTUAL_CURRENT"); read_value.template operator()<float>(space, "ACTUAL_GASFLOW"); read_value.template operator()<float>(space, "ACTUAL_POWER"); read_value.template operator()<float>(space, "ACTUAL_VOLTAGE"); read_value.template operator()<float>(space, "ACTUAL_WELDINGTIME"); read_value.template operator()<float>(space, "ACTUAL_WFS"); read_value.template operator()<float>(space, "DISPLAY_CURRENT"); read_value.template operator()<float>(space, "DISPLAY_ENERGY"); read_value.template operator()<float>(space, "DISPLAY_POWER"); read_value.template operator()<float>(space, "DISPLAY_VOLTAGE"); read_value.template operator()<float>(space, "DISPLAY_WFS"); read_value.template operator()<float>(space, "WIREBUFFER_VALUE"); read_value.template operator()<float>(space, "ERROR"); read_value.template operator()<bool>(space, "PROCESS_ACTIVE"); read_value.template operator()<std::string>(space, "FIRMWAREVERSION"); read_value.template operator()<std::string>(space, "SERIALNUMBER"); } } Loading