Ros2 Singleton

The Ros2 singleton provides interfaces to static methods and convenience methods.

In QML it is available as Ros2, e.g.:

if (Ros2.ok()) console.log("Ros2 is ok!")

ROS Initialization

First, you need to initialize the node used by your QML application, e.g., in the onCompleted handler:

Component.onCompleted: {
  Ros2.init("node_name")
}

You can also conditionally initialize by checking if it was already initialized using Ros2.isRosInitialized. As described in the API documentation for Ros2.init, you can pass either just the node name or additionally use provided command line args instead of the command line args provided to your executable.

Query Topics

You can also use the Ros2 singleton to query the available topics. Currently, three methods are provided:

  • QStringList queryTopics( const QString &datatype = QString())
    Queries a list of topics with the given datatype or all topics if no type provided.
  • QList<TopicInfo> queryTopicInfo()
    Retrieves a list of all advertised topics including their datatype. See TopicInfo
  • QString queryTopicType( const QString &name )
    Retrieves the datatype for a given topic.

Example:

// Retrieves a list of topics with the type sensor_msgs/Image
var topics = Ros2.queryTopics("sensor_msgs/msg/Image")
// Another slower and less clean method of this would be
var cameraTopics = []
var topics = Ros2.queryTopicInfo()
for (var i = 0; i < topics.length; ++i) {
  if (topics[i].datatype == "sensor_msgs/msg/Image") cameraTopics.push(topics[i].name)
}
// The type of a specific topic can be retrieved as follows
var datatype = Ros2.queryTopicType("/topic/that/i/care/about")
// Using this we can make an even worse implementation of the same functionality
var cameraTopics = []
var topics = Ros2.queryTopics() // Gets all topics
for (var i = 0; i < topics.length; ++i) {
  if (Ros2.queryTopicType(topics[i]) == "sensor_msgs/msg/Image") cameraTopics.push(topics[i])
}

Create Empty Message

You can also create empty messages and service requests as javascript objects using the Ros2 singleton.

var message = Ros2.createEmptyMessage("geometry_msgs/msg/Point")
// This creates an empty instance of the mssage, we can override the fields
message.x = 1; message.y = 2; message.z = 1

// Same can be done with service requests
var serviceRequest = Ros2.createEmptyServiceRequest("std_srvs/srv/SetBool")
// This creates an empty instance of the service request with all members set to their
// default, we can override the fields
serviceRequest.data = true

Logging

The Ros2 singleton also provides access to the Ros2 logging functionality. See Logging.

IO

You can also save and read data that can be serialized in the yaml format using:

var obj = {"key": [1, 2, 3], "other": "value"}
if (!Ros2.io.writeYaml("/home/user/file.yaml", obj))
  Ros2.error("Could not write file!")
// and read it back
obj = Ros2.io.readYaml("/home/user/file.yaml")
if (!obj) Ros2.error("Failed to load file!")

API

class TopicInfo

Properties

QString name

The name of the topic, e.g., /front_camera/image_raw.

QStringList datatypes

The datatype(s) of the topic, e.g., sensor_msgs/msg/Image.

class IO

Public Functions

bool writeYaml(QString path, const QVariant &value)

Writes the given value to the given path in the yaml format.

Parameters:
  • path – The path to the file.

  • value – The value to write.

Returns:

True if successful, false otherwise.

QVariant readYaml(QString path)

Reads a yaml file and returns the content in a QML compatible structure of ‘QVariantMap’s and ‘QVariantList’s.

Parameters:

path – The path to the file.

Returns:

A variant containing the file content or false.

class Ros2QmlSingletonWrapper : public QObject

Public Functions

void init(const QString &name, quint32 options = 0)

Initializes the ros node with the given name and the command line arguments passed from the command line.

Parameters:
  • name – The name of the ROS node.

  • options – The options passed to ROS, see ros_init_options::Ros2InitOption.

bool ok() const

Can be used to query the state of ROS.

Returns:

False if it’s time to exit, true if still ok.

qml_ros2_plugin::Time now() const
Returns:

The current time as given by the node’s clock (if initialized, otherwise rclcpp::Time())

QString getName()

Returns the name of the node. Returns empty string before ROS node was initialized.

QString getNamespace()

Returns the namespace of the node. Returns empty string before ROS node was initialized.

QStringList queryTopics(const QString &datatype = QString()) const

Queries the internal ndoe for its topics or using the optional datatype parameter for all topics with the given type.

Parameters:

datatype – The message type to filter topics for, e.g., sensor_msgs/Image. Omit to query for all topics.

Returns:

A list of topics that matches the given datatype or all topics if no datatype provided.

QList<qml_ros2_plugin::TopicInfo> queryTopicInfo() const

Queries the internal node for its topics and their type.

Returns:

A list of TopicInfo.

QStringList queryTopicTypes(const QString &name) const

Queries the internal node for a topic with the given name.

Parameters:

name – The name of the topic, e.g., /front_camera/image_raw.

Returns:

The types available on the topic if found, otherwise an empty string.

QVariant createEmptyMessage(const QString &datatype) const

Creates an empty message for the given message type, e.g., “geometry_msgs/Point”. If the message type is known, an empty message with all members set to their default is returned. If the message type is not found on the current machine, a warning message is printed and null is returned.

Parameters:

datatype – The message datatype.

Returns:

A message with all members set to their default.

QVariant createEmptyServiceRequest(const QString &datatype) const

Creates an empty service request for the given service type, e.g., “std_srvs/SetBool”. If the service type is known, an empty request is returned with all members of the request message set to their default values. If the service type is not found on the current machine, a warning message is printed and null is returned.

Parameters:

datatype – The service datatype. NOT the request datatype.

Returns:

A request message with all members set to their default.

QObject *getLogger(const QString &name = QString())

Get the logger with the given name or if no name is passed, the node’s logger.

Parameters:

name – (Optional) Name of the logger.

Returns:

An instance of Logger wrapping the requested rclcpp::Logger.

QJSValue debug()

Logs debug with the node’s logger.

QJSValue info()

Logs info with the node’s logger.

QJSValue warn()

Logs warn with the node’s logger.

QJSValue error()

Logs error with the node’s logger.

QJSValue fatal()

Logs fatal with the node’s logger.

QObject *createPublisher(const QString &topic, const QString &type, quint32 queue_size = 1)

Creates a Publisher to publish ROS messages.

Parameters:
  • type – The type of the messages published using this publisher.

  • topic – The topic on which the messages are published.

  • queue_size – The maximum number of outgoing messages to be queued for delivery to subscribers.

Returns:

A Publisher instance.

QObject *createSubscription(const QString &topic, quint32 queue_size = 0)

Creates a Subscriber to createSubscription to ROS messages. Convenience function to create a subscriber in a single line.

Parameters:
  • topic – The topic to createSubscription to.

  • queue_size – The maximum number of incoming messages to be queued for processing.

Returns:

A Subscriber instance.

QObject *createSubscription(const QString &topic, const QString &message_type, quint32 queue_size = 0)

Creates a Subscriber to createSubscription to ROS messages. Convenience function to create a subscriber in a single line.

Parameters:
  • topic – The topic to createSubscription to.

  • message_type – The type of the messages to subscribe to on the topic.

  • queue_size – The maximum number of incoming messages to be queued for processing.

Returns:

A Subscriber instance.

QObject *createServiceClient(const QString &name, const QString &type)

Creates a ServiceClient for the given type and the given name.

Parameters:
  • name – The name of the service to connect to.

  • type – The type of the service. Example: example_interfaces/srv/AddTwoInts

Returns:

An instance of ServiceClient.

QObject *createActionClient(const QString &name, const QString &type)

Creates an ActionClient for the given type and the given name.

Parameters:
  • name – The name of the action server to connect to.

  • type – The type of the action. Example: action_tutorials_interfaces/action/Fibonacci

Returns:

An instance of ActionClient.

Signals

void initialized()

Emitted once when ROS was initialized.

void shutdown()

Emitted when this ROS node was shut down and it is time to exit.