Ros Singleton

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

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

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

ROS Initialization

If you can not or for whatever reason do not want to initialize ROS in your C++ entry, you can also do it in QML, e.g., in the onCompleted handler:

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

You can also conditionally initialize by checking if it was already initialized using Ros.isInitialized. As described in the API documentation for Ros.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. In both cases, you can also pass the following RosInitOptions options:

  • NoSigintHandler:
    Don’t install a SIGINT (e.g., Ctrl+C on terminal) handler.
  • AnonymousName:
    Anonymize the node name. Adds a random number to the node’s name to make it unique.
  • NoRosout:
    Don’t broadcast rosconsole output to the /rosout topic. See Logging
Component.onCompleted: {
  Ros.init("node_name", RosInitOptions.AnonymousName | RosInitOptions.NoRosout)
}

Wait For Message

If you only require a single message from a topic, you can use the Ros.waitForMessageAsync method which asynchronously waits for a message on the given topic with an optional maximum duration to wait and once a message is received or the maximum wait duration elapsed, the callback method is called with the received message or null if the waiting timeouted.

Ros.waitForMessageAsync("/some_topic", 10000 /* wait for maximum 10 seconds */, function (msg) {
  if (!msg) {
    // Handle timeout
    return
  }
  // Handle message
}

Query Topics

You can also use the Ros 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 )
    Reterieves the datatype for a given topic.

Example:

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

Create Empty Message

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

var message = Ros.createEmptyMessage("geometry_msgs/Point")
// This creates an empty instance of the mssage, we can override the fields
message.x = 1; message.y = 2; message.z = 1
// However, note that we do not call custom message constructors, hence, if the message has different default values
// they will not be set here. This is a rarely known feature and not used often in ROS 1, though.

// Same can be done with service requests
var serviceRequest = Ros.createEmptyServiceRequest("std_srvs/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

Package API

The package property provides a wrapper for ros::package.

// Retrieve a list of all packages
var packages = Ros.package.getAll()
// Get the fully-qualified path to a specific package
var path = Ros.package.getPath("some_pkg")
// Get plugins for a package as a map [package_name -> [values]]
var plugins = Ros.package.getPlugins("rviz", "plugin")

Console

The Ros singleton also provides access to the Ros 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 (!Ros.io.writeYaml("/home/user/file.yaml", obj))
  Ros.error("Could not write file!")
// and read it back
obj = Ros.io.readYaml("/home/user/file.yaml")
if (!obj) Ros.error("Failed to load file!")

API

class Package

A wrapper for ros::package

Public Functions

QString command(const QString &cmd)

Runs a command of the form ‘rospack <cmd>’. (This does not make a subprocess call!)

Parameters

cmd – The command passed to rospack.

Returns

The output of the command as a string.

QString getPath(const QString &package_name)

Queries the path to a package.

Parameters

package_name – The name of the package.

Returns

The fully-qualified path to the given package or an empty string if the package is not found.

QStringList getAll()
Returns

A list of all packages.

QVariantMap getPlugins(const QString &name, const QString &attribute, bool force_recrawl = false)

Queries for all plugins exported for a given package.

<export>
  <name attribute="value"/>
  <rviz plugin="${prefix}/plugin_description.xml"/>
</export>

To query for rviz plugins you would pass ‘rviz’ as the name and ‘plugin’ as the attribute.

Parameters
  • name – The name of the export tag.

  • attribute – The name of the attribute for the value is obtained.

  • force_recrawl – Forces rospack to rediscover everything on the system before running the search.

Returns

A map with the name of the package exporting something for name as the key (string) and a QStringList containing all exported values as the value.

class TopicInfo

Public Functions

TopicInfo() = default

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

The datatype of the topic, e.g., sensor_msgs/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 RosQmlSingletonWrapper : public QObject

Public Functions

bool isInitialized() const

Checks whether ROS is initialized.

Returns

True if ROS is initialized, false otherwise.

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::RosInitOption.

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

Initializes the ros node with the given args.

Parameters
  • args – The args that are passed to ROS. Normally, these would be the command line arguments see init(const QString &, quint32)

  • name – The name of the ROS node.

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

bool ok() const

Can be used to query the state of ROS.

Returns

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

void spinOnce()

Processes a single round of callbacks. This call is non-blocking as the queue will be called on a detached thread. Not needed unless you disable the AsyncSpinner using setThreads(int) with the argument 0.

void setThreads(int count)

Sets the thread count for the AsyncSpinner. If asynchronous spinning is disabled, you have to manually call spinOnce() to receive and publish messages.

Parameters

count – How many threads the AsyncSpinner will use. Set to zero to disable spinning. Default: 1

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 ROS master 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<TopicInfo> queryTopicInfo() const

Queries the ROS master for its topics and their type.

Returns

A list of TopicInfo.

QString queryTopicType(const QString &name) const

Queries the ROS master for a topic with the given name.

Parameters

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

Returns

The type of 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.

void waitForMessageAsync(const QString &topic, const QJSValue &callback)

Waits for a single message on the given topic and once a message is received passes it to the given callback.

Parameters
  • topic – The topic the message is expected on.

  • callback – The callback that handles the received message.

void waitForMessageAsync(const QString &topic, double duration, const QJSValue &callback)

Waits for a single message on the given topic for the specified duration and once a message is received passes it to the given callback. If the duration elapsed without a message, the callback is called with null.

Parameters
  • topic – The topic the message is expected on.

  • duration – The maximum duration to wait in milliseconds.

  • callback – The callback that handles the received message or the timeout.

QJSValue debug()

Outputs a ROS debug message. The equivalent of calling ROS_DEBUG in C++. The signature in QML is debug(msg, consoleName) where consoleName is an optional parameter which defaults to ros.qml_ros_plugin.

Note: The msg is not a format string.

Example:

Ros.debug("The value of x is: " + x);

QJSValue info()

Outputs a ROS info message. The equivalent of calling ROS_INFO in C++. The signature in QML is info(msg, consoleName) where consoleName is an optional parameter which defaults to ros.qml_ros_plugin.

Note: The argument is not a format string.

Example:

Ros.info("The value of x is: " + x);

QJSValue warn()

Outputs a ROS warn message. The equivalent of calling ROS_WARN in C++. The signature in QML is warn(msg, consoleName) where consoleName is an optional parameter which defaults to ros.qml_ros_plugin.

Note: The argument is not a format string.

Example:

Ros.warn("The value of x is: " + x);

QJSValue error()

Outputs a ROS error message. The equivalent of calling ROS_ERROR in C++. The signature in QML is error(msg, consoleName) where consoleName is an optional parameter which defaults to ros.qml_ros_plugin.

Note: The argument is not a format string.

Example:

Ros.error("The value of x is: " + x);

QJSValue fatal()

Outputs a ROS fatal message. The equivalent of calling ROS_FATAL in C++. The signature in QML is fatal(msg, consoleName) where consoleName is an optional parameter which defaults to ros.qml_ros_plugin.

Note: The argument is not a format string.

Example:

Ros.fatal("The value of x is: " + x);

QObject *advertise(const QString &type, const QString &topic, quint32 queue_size, bool latch = false)

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.

  • latch – Whether or not this publisher should latch, i.e., always send out the last message to new subscribers.

Returns

A Publisher instance.

QObject *advertise(const QString &ns, const QString &type, const QString &topic, quint32 queue_size, bool latch = false)

Creates a Publisher to publish ROS messages.

Parameters
  • ns – The namespace for this publisher.

  • 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.

  • latch – Whether or not this publisher should latch, i.e., always send out the last message to new subscribers.

Returns

A Publisher instance.

QObject *subscribe(const QString &topic, quint32 queue_size)

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

Parameters
  • topic – The topic to subscribe to.

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

Returns

A Subscriber instance.

QObject *subscribe(const QString &ns, const QString &topic, quint32 queue_size)

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

Parameters
  • ns – The namespace for this Subscriber.

  • topic – The topic to subscribe to.

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

Returns

A Subscriber instance.

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

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

Parameters
  • type – The type of the action (which always ends with ‘Action’). Example: actionlib_tutorials/FibonacciAction

  • name – The name of the action server to connect to. This is essentially a base topic.

Returns

An instance of ActionClient.

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

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

Parameters
  • ns – The namespace for this ActionClient.

  • type – The type of the action (which always ends with ‘Action’). Example: actionlib_tutorials/FibonacciAction

  • name – The name of the action server to connect to. This is essentially a base topic.

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.