6#ifndef YARP_ROS2_ROS2UTILS_H
7#define YARP_ROS2_ROS2UTILS_H
9#include <rclcpp/rclcpp.hpp>
10#include <std_msgs/msg/header.hpp>
15 static rclcpp::Node::SharedPtr
createNode(std::string name);
16 static rclcpp::Node::SharedPtr
createNode(std::string name, rclcpp::NodeOptions& node_options);
builtin_interfaces::msg::Time ros2TimeFromYarp(double yarpTime)
double yarpTimeFromRos2(builtin_interfaces::msg::Time ros2Time)
static rclcpp::Node::SharedPtr createNode(std::string name)