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.
Additionally, you can use the init options to set options for the node, such as the namespace or domain id.
Component.onCompleted: {
let initOptions = Ros2.createInitOptions()
initOptions.setNamespace("/my_namespace")
initOptions.setDomainId(42) // or initOptions.useDefaultDomainId()
Ros2.init("node_name", initOptions)
}
Before application exit make sure to call Ros2.shutdown() to cleanly shutdown the node.
In Qt application this should be done automatically, if it is not, you might get a warning in the console and the
application could crash due to the middleware being destructed before the ROS 2 qml plugin cleaned up.
Query Graph
You can also use the Ros2 singleton to query the available topics, services and actions. These are available as:
QVariantMap getTopicNamesAndTypes()Retrieves a map of topic names and their types as a list of strings.QVariantMap getServiceNamesAndTypes()Retrieves a map of service names and their types as a list of strings.QVariantMap getActionNamesAndTypes()Retrieves a map of action names and their types as a list of strings.
Note that the return value is a QVariantMap, which is a wrapped QMap<QString, QStringList>
to make it compatible with QML.
Also check out the graph_queries.qml example in the repo’s examples folder.
Additionally, for topics three convenience methods are also 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 datatypes. SeeTopicInfoQString queryTopicTypes( const QString &name )Retrieves the datatypes for a given topic.
And for actions and services:
QStringList queryServices( const QString &datatype = QString())Queries a list of services with the given datatype or all services if no type provided.QStringList queryActions( const QString &datatype = QString())Queries a list of actions with the given datatype or all actions if no type provided.
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].datatypes.includes("sensor_msgs/msg/Image")) cameraTopics.push(topics[i].name)
}
// The types of a specific topic can be retrieved as follows
var datatypes = Ros2.queryTopicTypes("/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.queryTopicTypes(topics[i]).includes("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 Ros2InitOptions : public QObject
-
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.
-
bool writeYaml(QString path, const QVariant &value)
-
class QoSWrapper
Wrapper to enable setting QoS settings in QML. Defaults to 1 depth, best effort reliability and volatile durability.
Public Functions
-
qml_ros2_plugin::QoSWrapper reliable()
Sets the reliability policy to reliable. Returns the QoSWrapper for chaining.
-
qml_ros2_plugin::QoSWrapper best_effort()
Sets the reliability policy to best effort. Returns the QoSWrapper for chaining.
-
qml_ros2_plugin::QoSWrapper durability_volatile()
Sets the durability policy to volatile. Returns the QoSWrapper for chaining.
-
qml_ros2_plugin::QoSWrapper transient_local()
Sets the durability policy to transient local. Returns the QoSWrapper for chaining.
-
qml_ros2_plugin::QoSWrapper keep_all()
Sets the history policy to keep all messages. Returns the QoSWrapper for chaining.
-
qml_ros2_plugin::QoSWrapper keep_last(int depth)
Sets the history policy to keep last messages. Returns the QoSWrapper for chaining.
- Parameters:
depth – The number of messages to keep.
-
int depth() const
Returns the depth of the QoS policy. If history policy is set to keep_last, this is the number of messages to keep.
-
qml_ros2_plugin::QoSWrapper reliable()
-
class Ros2QmlSingletonWrapper : public QObject
Public Functions
-
QString hostname() const
Returns the hostname of the current machine.
-
QObject *createInitOptions()
Create a Ros2InitOptions object.
-
qml_ros2_plugin::QoSWrapper QoS()
Creates a default QoS object with Stefan Fabian’s recommended settings for UIs: best_effort and volatile with a history depth of 1.
-
qml_ros2_plugin::QoSWrapper BestAvailableQoS()
Creates a QoS wrapper with the settings for BestAvailable from rclcpp.
-
qml_ros2_plugin::QoSWrapper ClockQoS()
Creates a QoS wrapper with the settings for Clock from rclcpp.
-
qml_ros2_plugin::QoSWrapper SensorDataQoS()
Creates a QoS wrapper with the settings for SensorData from rclcpp.
-
qml_ros2_plugin::QoSWrapper ServicesQoS()
Creates a QoS wrapper with the settings for Services from rclcpp.
-
qml_ros2_plugin::QoSWrapper SystemDefaultsQoS()
Creates a QoS wrapper with the settings for SystemDefaults from rclcpp.
-
void shutdown()
Shutdown the internal node. Call before application exit to enable clean up.
-
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 node 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.
-
QVariantMap getTopicNamesAndTypes() const
Queries the internal node for its known topics and their types. See rclcpp::Node::get_topic_names_and_types() for more information.
- Returns:
A map with the topic names as keys and the types as values.
-
QStringList queryServices(const QString &datatype = QString()) const
Queries the internal node for its services or using the optional datatype parameter for all services with the given type.
- Parameters:
datatype – The message type to filter services for, e.g., std_srvs/srv/SetBool. Omit to query for all services.
- Returns:
A list of services that matches the given datatype or all services if no datatype provided.
-
QVariantMap getServiceNamesAndTypes() const
Queries the internal node for its known services and their types. See rclcpp::Node::get_service_names_and_types() for more information.
- Returns:
A map with the service names as keys and the types as values.
-
QStringList queryActions(const QString &datatype = QString()) const
Queries the internal node for all available actions or using the optional datatype parameter for all actions with the given type.
- Parameters:
datatype – The message type to filter actions for, e.g., control_msgs/action/FollowJointTrajectory. Omit to query for all actions.
- Returns:
A list of actions that matches the given datatype or all actions if no datatype provided.
-
QVariantMap getActionNamesAndTypes() const
Queries the internal node for its known actions and their types.
- Returns:
A map with the action names as keys and the types as values.
-
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.
-
QVariant createEmptyActionGoal(const QString &datatype) const
Creates an empty action goal request for the given action type, e.g., “example_interfaces/action/Fibonacci”. If the action type is known, an empty goal request is returned with all members of the goal message set to their default values. If the action type is not found on the current machine, a warning message is printed and null is returned.
- Parameters:
datatype – The action datatype. NOT the goal datatype.
- Returns:
A goal 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, const qml_ros2_plugin::QoSWrapper &qos)
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.
- Returns:
A Publisher instance.
-
QObject *createPublisher(const QString &topic, const QString &type, quint32 queue_size = 10)
-
- Parameters:
queue_size – Sets the keep_last history of the qos to the given value.
-
QObject *createSubscription(const QString &topic, const qml_ros2_plugin::QoSWrapper &qos)
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.
qos – The QoS settings for the subscription.
- Returns:
A Subscriber instance.
-
QObject *createSubscription(const QString &topic, quint32 queue_size = 1)
-
- Parameters:
queue_size – The keep_last history of the qos. Default: 1
-
QObject *createSubscription(const QString &topic, const QString &message_type, const qml_ros2_plugin::QoSWrapper &qos)
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 *createSubscription(const QString &topic, const QString &message_type, quint32 queue_size = 1)
-
- Parameters:
queue_size – The keep_last history of the qos. Default: 1
-
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 *createServiceClient(const QString &name, const QString &type, const qml_ros2_plugin::QoSWrapper &qos)
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
qos – The QoS settings for the service client.
- 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.
-
QString hostname() const