├── qmldir ├── rosqmlplugin.dsv.in ├── .gitignore ├── hooks ├── ros_qml_plugin.dsv.in └── ros_qml_plugin.sh.in ├── doc └── screenshot-sample-app.png ├── include └── ros_qml_plugin │ ├── qml_set_expression_skill.hpp │ ├── qobject_ros2.hpp │ ├── qml_rossignal.hpp │ ├── qml_sayskill.hpp │ ├── qml_navigate_skill.hpp │ ├── ros.hpp │ ├── qml_chatskill.hpp │ ├── qml_rosparam.hpp │ ├── ros2.hpp │ ├── qml_look_at_skill.hpp │ ├── qml_rosaction.hpp │ ├── ros_types.hpp │ ├── qml_rosservice.hpp │ └── qml_rostopic.hpp ├── src ├── image_provider.hpp ├── qml_set_expression_skill.cpp ├── qml_rossignal.cpp ├── qobject_ros2.cpp ├── qml_rosaction.cpp ├── ros2.cpp ├── qml_sayskill.cpp ├── image_provider.cpp ├── qml_navigate_skill.cpp ├── rosplugin.cpp ├── qml_chatskill.cpp ├── qml_look_at_skill.cpp ├── qml_rosservice.cpp ├── qml_rosparam.cpp └── qml_rostopic.cpp ├── package.xml ├── examples └── sample.qml ├── CMakeLists.txt ├── README.md ├── CHANGELOG.rst └── LICENSE /qmldir: -------------------------------------------------------------------------------- 1 | module Ros 2 | plugin ros_qml_plugin 3 | 4 | -------------------------------------------------------------------------------- /rosqmlplugin.dsv.in: -------------------------------------------------------------------------------- 1 | prepend-non-duplicate;QML2_IMPORT_PATH;lib 2 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | #Qt 2 | *.user 3 | build*/ 4 | 5 | #YCM 6 | *.pyc 7 | 8 | -------------------------------------------------------------------------------- /hooks/ros_qml_plugin.dsv.in: -------------------------------------------------------------------------------- 1 | prepend-non-duplicate;QML2_IMPORT_PATH;lib/ 2 | -------------------------------------------------------------------------------- /hooks/ros_qml_plugin.sh.in: -------------------------------------------------------------------------------- 1 | ament_prepend_unique_value QML2_IMPORT_PATH "$AMENT_CURRENT_PREFIX/lib/" 2 | -------------------------------------------------------------------------------- /doc/screenshot-sample-app.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros4hri/ros-qml-plugin/HEAD/doc/screenshot-sample-app.png -------------------------------------------------------------------------------- /include/ros_qml_plugin/qml_set_expression_skill.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2025 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #ifndef ROS_QML_PLUGIN__QML_SET_EXPRESSION_SKILL_HPP_ 16 | #define ROS_QML_PLUGIN__QML_SET_EXPRESSION_SKILL_HPP_ 17 | 18 | #include 19 | #include 20 | #include 21 | 22 | #include 23 | #include 24 | 25 | #include "ros_qml_plugin/qobject_ros2.hpp" 26 | 27 | class SetExpressionSkill : public QObjectRos2 28 | { 29 | Q_OBJECT 30 | 31 | public: 32 | SetExpressionSkill(); 33 | Q_INVOKABLE void set_expression(QString expression); 34 | Q_INVOKABLE void set_expression(float valence, float arousal); 35 | 36 | private: 37 | typename rclcpp::Publisher::SharedPtr _publisher; 38 | }; 39 | 40 | #endif // ROS_QML_PLUGIN__QML_SET_EXPRESSION_SKILL_HPP_ 41 | -------------------------------------------------------------------------------- /src/image_provider.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2024 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #ifndef IMAGE_PROVIDER_HPP_ 16 | #define IMAGE_PROVIDER_HPP_ 17 | 18 | #include 19 | 20 | #include 21 | #include 22 | #include 23 | #include 24 | #include 25 | 26 | #include 27 | #include 28 | 29 | class RosImageProvider : public QQuickImageProvider 30 | { 31 | public: 32 | RosImageProvider(); 33 | 34 | QImage requestImage( 35 | const QString & id, QSize * size, 36 | const QSize & requestedSize); 37 | 38 | ImageType imageType() const override {return QQmlImageProviderBase::Image;} 39 | 40 | private: 41 | std::string _topic; 42 | 43 | void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr & msg); 44 | 45 | std::shared_ptr _sub; 46 | 47 | QImage _last_image; 48 | }; 49 | 50 | #endif // IMAGE_PROVIDER_HPP_ 51 | -------------------------------------------------------------------------------- /src/qml_set_expression_skill.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2025 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | 16 | #include "ros_qml_plugin/qml_set_expression_skill.hpp" 17 | #include "ros_qml_plugin/ros2.hpp" 18 | 19 | 20 | SetExpressionSkill::SetExpressionSkill() 21 | { 22 | std::shared_ptr node = Ros2Qml::getInstance().node(); 23 | _publisher = node->create_publisher( 24 | "/skill/set_expression", 1); 25 | } 26 | 27 | void SetExpressionSkill::set_expression(QString expression) 28 | { 29 | interaction_skills::msg::SetExpression message; 30 | 31 | message.expression.expression = expression.toStdString(); 32 | 33 | _publisher->publish(message); 34 | } 35 | 36 | void SetExpressionSkill::set_expression(float valence, float arousal) 37 | { 38 | interaction_skills::msg::SetExpression message; 39 | 40 | message.expression.valence = valence; 41 | message.expression.arousal = arousal; 42 | 43 | _publisher->publish(message); 44 | } 45 | -------------------------------------------------------------------------------- /include/ros_qml_plugin/qobject_ros2.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full 3 | // license information. 4 | 5 | #ifndef ROS_QML_PLUGIN__QOBJECT_ROS2_HPP_ 6 | #define ROS_QML_PLUGIN__QOBJECT_ROS2_HPP_ 7 | 8 | #include 9 | 10 | /*! 11 | * Base class for QObjects that require ROS functionality. 12 | * Provides virtual methods that are called once ROS was initialized and once it 13 | * was shutdown to enable initialization and clean-up of of functionality that 14 | * requires ROS. 15 | */ 16 | class QObjectRos2 : public QObject 17 | { 18 | Q_OBJECT 19 | 20 | public: 21 | explicit QObjectRos2(QObject * parent = nullptr); 22 | 23 | ~QObjectRos2() override; 24 | 25 | //! @return Whether or not this object is initialized. 26 | bool isRosInitialized() const; 27 | 28 | protected: 29 | /*! 30 | * Called once ROS was initialized in this application. 31 | * 32 | * Override to perform initialization of functionality that depends on ROS. 33 | */ 34 | virtual void onRos2Initialized() {} 35 | 36 | /*! 37 | * Called once ROS or the application shuts down. 38 | * 39 | * Override to perform clean-up of functionality that depends on ROS, e.g., if 40 | * the destruction order does not guarantee destruction before required ROS 41 | * objects are destructed. 42 | */ 43 | virtual void onRos2Shutdown() {} 44 | 45 | public slots: 46 | void _initialize(); 47 | 48 | void _shutdown(); 49 | 50 | private: 51 | bool is_initialized_; 52 | }; 53 | 54 | #endif // ROS_QML_PLUGIN__QOBJECT_ROS2_HPP_ 55 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros_qml_plugin 5 | 2.22.0 6 | A QML plugin to interact with ROS 2 from QtQuick applications 7 | Séverin Lemaignan 8 | Apache-2.0 9 | 10 | ament_cmake_auto 11 | 12 | hri_msgs 13 | hri_actions_msgs 14 | image_transport 15 | image_transport_plugins 16 | i18n_msgs 17 | libqt5-core 18 | libqt5-multimedia 19 | libqt5-qml 20 | libqt5-quick 21 | rclcpp 22 | rclcpp_action 23 | std_msgs 24 | std_srvs 25 | ui_msgs 26 | kb_msgs 27 | 28 | communication_skills 29 | interaction_skills 30 | navigation_skills 31 | geometry_msgs 32 | backward_ros 33 | 34 | qtbase5-dev 35 | qtdeclarative5-dev 36 | qtmultimedia5-dev 37 | 38 | 39 | ament_lint_auto 40 | ament_lint_common 41 | 42 | 43 | ament_cmake 44 | 45 | 46 | -------------------------------------------------------------------------------- /src/qml_rossignal.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2024 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #include "ros_qml_plugin/qml_rossignal.hpp" 16 | #include "ros_qml_plugin/ros2.hpp" 17 | 18 | using std::placeholders::_1; 19 | 20 | void RosSignal::setTopic(QString topic) 21 | { 22 | if (topic == _topic) { 23 | return; 24 | } 25 | 26 | std::shared_ptr node = Ros2Qml::getInstance().node(); 27 | 28 | _subscriber = node->create_subscription( 29 | topic.toStdString(), 1, 30 | std::bind(&RosSignal::onIncomingSignal, this, _1)); 31 | 32 | _publisher = 33 | node->create_publisher(topic.toStdString(), 1); 34 | 35 | _topic = topic; 36 | } 37 | 38 | void RosSignal::onIncomingSignal(const std_msgs::msg::Empty /* msg */) 39 | { 40 | emit triggered(); 41 | } 42 | 43 | void RosSignal::signal() 44 | { 45 | if (std::string(_publisher->get_topic_name()).empty()) { 46 | std::cerr << "RosSignal.signal() called without any topic." << std::endl; 47 | return; 48 | } 49 | 50 | _publisher->publish(std_msgs::msg::Empty()); 51 | } 52 | -------------------------------------------------------------------------------- /src/qobject_ros2.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full 3 | // license information. 4 | 5 | #include 6 | 7 | #include "ros_qml_plugin/qobject_ros2.hpp" 8 | #include "ros_qml_plugin/ros2.hpp" 9 | 10 | QObjectRos2::QObjectRos2(QObject * parent) 11 | : QObject(parent), is_initialized_(false) 12 | { 13 | if (Ros2Qml::getInstance().isInitialized()) { 14 | // Invoke initialize after object was constructed 15 | QMetaObject::invokeMethod(this, "_initialize", Qt::QueuedConnection); 16 | } else { 17 | QObject::connect( 18 | &Ros2Qml::getInstance(), &Ros2Qml::initialized, this, 19 | &QObjectRos2::_initialize); 20 | } 21 | // These allow for safe clean-up if the application exits since the order of 22 | // the singleton destructors is undefined and this might lead to dependency 23 | // issues. 24 | QObject::connect( 25 | &Ros2Qml::getInstance(), &Ros2Qml::shutdown, this, 26 | &QObjectRos2::_shutdown); 27 | QObject::connect( 28 | QCoreApplication::instance(), &QCoreApplication::aboutToQuit, 29 | this, &QObjectRos2::_shutdown); 30 | // This object needs ROS communication, so it's safe to assume it wants the 31 | // spinner to be running during its lifetime. 32 | Ros2Qml::getInstance().registerDependant(); 33 | } 34 | 35 | QObjectRos2::~QObjectRos2() {Ros2Qml::getInstance().unregisterDependant();} 36 | 37 | bool QObjectRos2::isRosInitialized() const {return is_initialized_;} 38 | 39 | void QObjectRos2::_initialize() 40 | { 41 | if (is_initialized_) { 42 | return; 43 | } 44 | onRos2Initialized(); 45 | is_initialized_ = true; 46 | } 47 | 48 | void QObjectRos2::_shutdown() 49 | { 50 | if (!is_initialized_) { 51 | return; 52 | } 53 | onRos2Shutdown(); 54 | is_initialized_ = false; 55 | } 56 | -------------------------------------------------------------------------------- /include/ros_qml_plugin/qml_rossignal.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2024 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #ifndef ROS_QML_PLUGIN__QML_ROSSIGNAL_HPP_ 16 | #define ROS_QML_PLUGIN__QML_ROSSIGNAL_HPP_ 17 | 18 | #include 19 | #include 20 | #include 21 | #include 22 | #include 23 | 24 | #include 25 | #include 26 | 27 | #include "ros_qml_plugin/qobject_ros2.hpp" 28 | 29 | /** 30 | * @brief The RosSignal class provides a QML object that publishes on a 31 | * configurable topic an empty message (ie, a signal) every time signal() is 32 | * called. 33 | */ 34 | class RosSignal : public QObjectRos2 35 | { 36 | Q_OBJECT 37 | Q_PROPERTY(QString topic WRITE setTopic MEMBER _topic) 38 | 39 | public: 40 | RosSignal() {} 41 | 42 | virtual ~RosSignal() {} 43 | 44 | void setTopic(QString topic); 45 | 46 | Q_INVOKABLE void signal(); 47 | 48 | void onIncomingSignal(const std_msgs::msg::Empty); 49 | 50 | signals: 51 | void triggered(); 52 | 53 | private: 54 | QString _topic; 55 | 56 | rclcpp::Publisher::SharedPtr _publisher; 57 | rclcpp::Subscription::SharedPtr _subscriber; 58 | }; 59 | 60 | #endif // ROS_QML_PLUGIN__QML_ROSSIGNAL_HPP_ 61 | -------------------------------------------------------------------------------- /include/ros_qml_plugin/qml_sayskill.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2025 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #ifndef ROS_QML_PLUGIN__QML_SAYSKILL_HPP_ 16 | #define ROS_QML_PLUGIN__QML_SAYSKILL_HPP_ 17 | 18 | #include 19 | #include 20 | #include 21 | 22 | #include 23 | #include 24 | #include 25 | 26 | #include "ros_qml_plugin/qobject_ros2.hpp" 27 | #include "ros_qml_plugin/qml_rosaction.hpp" 28 | 29 | class SaySkill : public RosActionImpl 30 | { 31 | Q_OBJECT 32 | Q_PROPERTY(QString personId MEMBER _person_id) 33 | Q_PROPERTY(QString groupId MEMBER _group_id) 34 | Q_PROPERTY(QString errorMsg MEMBER _error_msg) 35 | 36 | public: 37 | Q_INVOKABLE void say(QString input); 38 | 39 | private: 40 | QString _person_id; 41 | QString _group_id; 42 | QString _error_msg; 43 | 44 | void goal_response_callback( 45 | rclcpp_action::ClientGoalHandle::SharedPtr); 46 | void feedback_callback( 47 | rclcpp_action::ClientGoalHandle::SharedPtr, 48 | const std::shared_ptr); 49 | void result_callback( 50 | const rclcpp_action::ClientGoalHandle::WrappedResult &); 51 | }; 52 | 53 | 54 | #endif // ROS_QML_PLUGIN__QML_SAYSKILL_HPP_ 55 | -------------------------------------------------------------------------------- /include/ros_qml_plugin/qml_navigate_skill.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2025 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #ifndef ROS_QML_PLUGIN__QML_NAVIGATE_SKILL_HPP_ 16 | #define ROS_QML_PLUGIN__QML_NAVIGATE_SKILL_HPP_ 17 | 18 | #include 19 | #include 20 | #include 21 | 22 | #include 23 | #include 24 | #include 25 | 26 | #include "ros_qml_plugin/qobject_ros2.hpp" 27 | #include "ros_qml_plugin/qml_rosaction.hpp" 28 | 29 | class NavigateSkill : public RosActionImpl 30 | { 31 | Q_OBJECT 32 | Q_PROPERTY(QVariant pose MEMBER _pose) 33 | Q_PROPERTY(QString target MEMBER _target) 34 | Q_PROPERTY(QString errorMsg MEMBER _error_msg) 35 | 36 | public: 37 | Q_INVOKABLE void navigate(const QVariant & target); 38 | 39 | private: 40 | QVariant _pose; 41 | QString _target; 42 | QString _error_msg; 43 | 44 | void goal_response_callback( 45 | rclcpp_action::ClientGoalHandle::SharedPtr); 46 | void feedback_callback( 47 | rclcpp_action::ClientGoalHandle::SharedPtr, 48 | const std::shared_ptr); 49 | void result_callback( 50 | const rclcpp_action::ClientGoalHandle:: 51 | WrappedResult &); 52 | }; 53 | 54 | 55 | #endif // ROS_QML_PLUGIN__QML_NAVIGATE_SKILL_HPP_ 56 | -------------------------------------------------------------------------------- /include/ros_qml_plugin/ros.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2025 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #pragma once 16 | 17 | #include 18 | #include 19 | #include "ros_qml_plugin/ros_types.hpp" 20 | 21 | /** Singleton class to provide a QML interface for ROS functionality. 22 | * This class allows creating ROS points and can be extended to include more 23 | * ROS-related functionalities. 24 | */ 25 | class Ros : public QObject 26 | { 27 | Q_OBJECT 28 | 29 | public: 30 | explicit Ros(QObject * parent = nullptr) 31 | : QObject(parent) {} 32 | 33 | Q_INVOKABLE QVariant point(const QString & frame, double x, double y, double z) 34 | { 35 | return QVariant::fromValue(RosPoint(frame, x, y, z)); 36 | } 37 | 38 | Q_INVOKABLE QVariant point(double x, double y, double z) 39 | { 40 | return QVariant::fromValue(RosPoint(x, y, z)); 41 | } 42 | 43 | Q_INVOKABLE QVariant pose(const QString & frame, double x, double y, double z) 44 | { 45 | return QVariant::fromValue(RosPose(frame, x, y, z)); 46 | } 47 | 48 | Q_INVOKABLE QVariant pose(double x, double y, double z) 49 | { 50 | return QVariant::fromValue(RosPose(x, y, z)); 51 | } 52 | 53 | Q_INVOKABLE QVariant pose( 54 | const QString & frame, double x, double y, double z, double qx, 55 | double qy, double qz, double qw) 56 | { 57 | return QVariant::fromValue(RosPose(frame, x, y, z, qx, qy, qz, qw)); 58 | } 59 | 60 | Q_INVOKABLE QVariant pose( 61 | double x, double y, double z, double qx, double qy, double qz, double qw) 62 | { 63 | return QVariant::fromValue(RosPose(x, y, z, qx, qy, qz, qw)); 64 | } 65 | }; 66 | -------------------------------------------------------------------------------- /include/ros_qml_plugin/qml_chatskill.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2025 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #ifndef ROS_QML_PLUGIN__QML_CHATSKILL_HPP_ 16 | #define ROS_QML_PLUGIN__QML_CHATSKILL_HPP_ 17 | 18 | #include 19 | #include 20 | #include 21 | 22 | #include 23 | #include 24 | #include 25 | 26 | #include "ros_qml_plugin/qobject_ros2.hpp" 27 | #include "ros_qml_plugin/qml_rosaction.hpp" 28 | 29 | class ChatSkill : public RosActionImpl 30 | { 31 | Q_OBJECT 32 | Q_PROPERTY(QString personId MEMBER _person_id) 33 | Q_PROPERTY(QString groupId MEMBER _group_id) 34 | Q_PROPERTY(QString errorMsg MEMBER _error_msg) 35 | 36 | public: 37 | Q_INVOKABLE void start(QString prompt = "", QString initial_input = ""); 38 | Q_INVOKABLE void stop(); 39 | 40 | private: 41 | QString _person_id; 42 | QString _group_id; 43 | QString _error_msg; 44 | 45 | std::shared_future::SharedPtr> 46 | _goal_handle_future; 47 | 48 | void goal_response_callback( 49 | rclcpp_action::ClientGoalHandle::SharedPtr); 50 | void feedback_callback( 51 | rclcpp_action::ClientGoalHandle::SharedPtr, 52 | const std::shared_ptr); 53 | void result_callback( 54 | const rclcpp_action::ClientGoalHandle::WrappedResult &); 55 | }; 56 | 57 | 58 | #endif // ROS_QML_PLUGIN__QML_CHATSKILL_HPP_ 59 | -------------------------------------------------------------------------------- /include/ros_qml_plugin/qml_rosparam.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2024 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #ifndef ROS_QML_PLUGIN__QML_ROSPARAM_HPP_ 16 | #define ROS_QML_PLUGIN__QML_ROSPARAM_HPP_ 17 | 18 | #include 19 | #include 20 | #include 21 | #include 22 | #include 23 | #include 24 | 25 | #include 26 | 27 | #include "ros_qml_plugin/qobject_ros2.hpp" 28 | 29 | typedef rclcpp::Subscription::SharedPtr 30 | ParameterEventSubscription; 31 | 32 | class RosParam : public QObjectRos2 33 | { 34 | Q_OBJECT 35 | Q_PROPERTY(QString node MEMBER _target_node_name) 36 | Q_PROPERTY(QString name MEMBER _name) 37 | Q_PROPERTY(QVariant value WRITE setValue MEMBER _value NOTIFY onValueChanged) 38 | 39 | public: 40 | RosParam(); 41 | 42 | virtual ~RosParam() {} 43 | 44 | void setValue(QVariant value); 45 | 46 | void onRos2Initialized(); 47 | 48 | signals: 49 | void onValueChanged(); 50 | 51 | private: 52 | // for local parameters 53 | rcl_interfaces::msg::SetParametersResult 54 | onLocalParameterEvent(const std::vector & parameters); 55 | 56 | rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr _local_cb; 57 | 58 | // for remote parameters 59 | rclcpp::AsyncParametersClient::SharedPtr _param_client; 60 | 61 | void onRemoteParameterEvent( 62 | const rcl_interfaces::msg::ParameterEvent::SharedPtr event); 63 | 64 | ParameterEventSubscription _remote_cb; 65 | 66 | ////////////////// 67 | bool _is_ready = false; 68 | QString _target_node_name; 69 | QString _name; 70 | QVariant _value; 71 | rclcpp::Node::SharedPtr _node; 72 | }; 73 | 74 | #endif // ROS_QML_PLUGIN__QML_ROSPARAM_HPP_ 75 | -------------------------------------------------------------------------------- /include/ros_qml_plugin/ros2.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full 3 | // license information. 4 | 5 | #ifndef ROS_QML_PLUGIN__ROS2_HPP_ 6 | #define ROS_QML_PLUGIN__ROS2_HPP_ 7 | 8 | #include 9 | #include 10 | #include 11 | #include 12 | 13 | #include 14 | #include 15 | 16 | class Ros2Qml : public QObject 17 | { 18 | Q_OBJECT 19 | 20 | private: 21 | Ros2Qml(); 22 | 23 | public: 24 | static Ros2Qml & getInstance(); 25 | 26 | Ros2Qml(const Ros2Qml &) = delete; 27 | 28 | void operator=(const Ros2Qml &) = delete; 29 | 30 | /*! 31 | * Checks whether ROS is initialized. 32 | * @return True if ROS is initialized, false otherwise. 33 | */ 34 | bool isInitialized() const; 35 | 36 | /*! 37 | * Initializes the ros node with the given name and the command line arguments 38 | * passed from the command line. 39 | * @param name The name of the ROS node. 40 | * @param options The options passed to ROS, see 41 | * ros_init_options::Ros2InitOption. 42 | */ 43 | void init(const QString & name, quint32 options = 0); 44 | 45 | /*! 46 | * Initializes the ros node with the given args. 47 | * @param name The name of the ROS node. 48 | * @param args The args that are passed to ROS. Normally, these would be the 49 | * command line arguments see init(const QString &, quint32) 50 | * @param options The options passed to ROS, see 51 | * ros_init_options::Ros2InitOption. 52 | */ 53 | void init(const QString & name, const QStringList & args, quint32 options = 0); 54 | 55 | /*! 56 | * Can be used to query the state of ROS. 57 | * @return False if it's time to exit, true if still ok. 58 | */ 59 | bool ok() const; 60 | 61 | //! Increases the dependant counter. 62 | void registerDependant(); 63 | 64 | //! Decreases the dependant counter and if it gets to 0, frees all memory. 65 | void unregisterDependant(); 66 | 67 | std::shared_ptr node(); 68 | std::shared_ptr image_transport(); 69 | 70 | signals: 71 | //! Emitted once when ROS was initialized. 72 | void initialized(); 73 | 74 | //! Emitted when this ROS node was shut down and it is time to exit. 75 | void shutdown(); 76 | 77 | protected slots: 78 | // void checkShutdown(); 79 | 80 | private: 81 | // void onInitialized(); 82 | 83 | std::thread executor_thread_; 84 | std::shared_ptr context_; 85 | std::shared_ptr node_; 86 | std::shared_ptr it_; 87 | 88 | std::atomic count_wrappers; 89 | }; 90 | 91 | #endif // ROS_QML_PLUGIN__ROS2_HPP_ 92 | -------------------------------------------------------------------------------- /include/ros_qml_plugin/qml_look_at_skill.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2025 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #ifndef ROS_QML_PLUGIN__QML_LOOK_AT_SKILL_HPP_ 16 | #define ROS_QML_PLUGIN__QML_LOOK_AT_SKILL_HPP_ 17 | 18 | #include 19 | #include 20 | #include 21 | 22 | #include 23 | #include 24 | #include 25 | 26 | #include "ros_qml_plugin/qobject_ros2.hpp" 27 | #include "ros_qml_plugin/qml_rosaction.hpp" 28 | 29 | 30 | #define SHARED_CONSTANT(type, name, value) \ 31 | Q_PROPERTY(type name READ name CONSTANT) \ 32 | type name() const {return value;} 33 | 34 | 35 | class LookAtSkill : public RosActionImpl 36 | { 37 | Q_OBJECT 38 | Q_PROPERTY(QString errorMsg MEMBER _error_msg) 39 | 40 | // policies 41 | SHARED_CONSTANT( 42 | QString, AUTO, 43 | QString::fromStdString(interaction_skills::action::LookAt::Goal::AUTO)) 44 | SHARED_CONSTANT( 45 | QString, RESET, 46 | QString::fromStdString(interaction_skills::action::LookAt::Goal::RESET)) 47 | SHARED_CONSTANT( 48 | QString, RANDOM, 49 | QString::fromStdString(interaction_skills::action::LookAt::Goal::RANDOM)) 50 | SHARED_CONSTANT( 51 | QString, SOCIAL, 52 | QString::fromStdString(interaction_skills::action::LookAt::Goal::SOCIAL)) 53 | SHARED_CONSTANT( 54 | QString, GLANCE, 55 | QString::fromStdString(interaction_skills::action::LookAt::Goal::GLANCE)) 56 | 57 | public: 58 | Q_INVOKABLE void look_at(QVariant target, const QString & policy = ""); 59 | Q_INVOKABLE void glance(QVariant target); 60 | Q_INVOKABLE void look_at_faces(); 61 | Q_INVOKABLE void look_around_randomly(); 62 | Q_INVOKABLE void reset(); 63 | 64 | private: 65 | QString _error_msg; 66 | 67 | void goal_response_callback( 68 | rclcpp_action::ClientGoalHandle::SharedPtr); 69 | void feedback_callback( 70 | rclcpp_action::ClientGoalHandle::SharedPtr, 71 | const std::shared_ptr); 72 | void result_callback( 73 | const rclcpp_action::ClientGoalHandle::WrappedResult &); 74 | }; 75 | 76 | 77 | #endif // ROS_QML_PLUGIN__QML_LOOK_AT_SKILL_HPP_ 78 | -------------------------------------------------------------------------------- /examples/sample.qml: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2024 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | import QtQuick 2.12 16 | import QtQuick.Window 2.12 17 | import QtQuick.Controls 2.15 18 | 19 | import Ros 2.0 20 | 21 | Window { 22 | visible: true 23 | width: 640 24 | height: 480 25 | title: qsTr("ROS2-QML sample app") 26 | 27 | 28 | Image { 29 | id: img 30 | cache: false 31 | 32 | anchors.fill: parent 33 | opacity: 0.5 34 | source: "image://rosimage/camera/image_raw" 35 | 36 | Timer { 37 | interval: 50 38 | repeat: true 39 | running: true 40 | onTriggered: { img.source = ""; img.source = "image://rosimage/camera/image_raw" } 41 | } 42 | } 43 | 44 | Label { 45 | id: label 46 | text: "publish a string on /input to change this text" 47 | anchors.centerIn: parent 48 | } 49 | 50 | StringTopic { 51 | topic: "input" 52 | isPublisher: false 53 | onValueChanged: { 54 | label.text = value; 55 | } 56 | } 57 | 58 | StringTopic{ 59 | id: hello_publisher 60 | isSubscriber: false 61 | topic: "hello" 62 | 63 | } 64 | 65 | Button { 66 | id: btn 67 | 68 | anchors.horizontalCenter: parent.horizontalCenter 69 | anchors.top: label.bottom 70 | anchors.topMargin: 20 71 | 72 | property int count: 0 73 | 74 | text: "Click me to publish a string on /hello" 75 | onClicked: { 76 | count += 1; 77 | hello_publisher.value = "Hello world - click #" + count; 78 | } 79 | 80 | } 81 | Label { 82 | id: label2 83 | 84 | anchors.horizontalCenter: parent.horizontalCenter 85 | anchors.top: btn.bottom 86 | anchors.topMargin: 20 87 | 88 | text: "publish an empty msg on /signal to toggle the blue square" 89 | } 90 | 91 | RosSignal { 92 | topic: "signal" 93 | onTriggered: semaphore.visible = !semaphore.visible 94 | } 95 | 96 | Rectangle { 97 | id: semaphore 98 | 99 | anchors.horizontalCenter: parent.horizontalCenter 100 | anchors.top: label2.bottom 101 | anchors.topMargin: 20 102 | 103 | width: 10 104 | height: 10 105 | 106 | visible: false 107 | color: "blue" 108 | } 109 | 110 | } 111 | -------------------------------------------------------------------------------- /include/ros_qml_plugin/qml_rosaction.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2024 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #ifndef ROS_QML_PLUGIN__QML_ROSACTION_HPP_ 16 | #define ROS_QML_PLUGIN__QML_ROSACTION_HPP_ 17 | 18 | #include 19 | #include 20 | #include 21 | 22 | #include 23 | #include 24 | #include 25 | 26 | #include "ros_qml_plugin/qobject_ros2.hpp" 27 | #include "ros_qml_plugin/ros2.hpp" 28 | 29 | class RosAction : public QObjectRos2 30 | { 31 | Q_OBJECT 32 | Q_PROPERTY(QString action WRITE setAction MEMBER _action) 33 | 34 | public: 35 | RosAction() {} 36 | virtual ~RosAction() {} 37 | 38 | virtual void setAction(const QString &) = 0; 39 | 40 | signals: 41 | void goalRejected(); 42 | void feedbackReceived(); 43 | void resultReceived(); 44 | 45 | protected: 46 | QString _action; 47 | }; 48 | 49 | /////////////////////////////////////////////////////////////////////////////// 50 | 51 | template 52 | class RosActionImpl : public RosAction 53 | { 54 | public: 55 | RosActionImpl() {} 56 | virtual ~RosActionImpl() {} 57 | 58 | void setAction(const QString & action) 59 | { 60 | if (action == _action) { 61 | return; 62 | } 63 | 64 | std::shared_ptr node = Ros2Qml::getInstance().node(); 65 | 66 | _client = rclcpp_action::create_client( 67 | node, action.toStdString()); 68 | } 69 | 70 | protected: 71 | typename rclcpp_action::Client::SharedPtr _client; 72 | rclcpp::CallbackGroup::SharedPtr _cb_group; 73 | }; 74 | 75 | /////////////////////////////////////////////////////////////////////////////// 76 | 77 | class SetLocaleAction : public RosActionImpl 78 | { 79 | Q_OBJECT 80 | Q_PROPERTY(QString locale MEMBER _locale) 81 | Q_PROPERTY(QString errorMsg MEMBER _error_msg) 82 | Q_PROPERTY(QString progress MEMBER _progress) 83 | 84 | public: 85 | Q_INVOKABLE void sendGoal(); 86 | 87 | private: 88 | QString _locale; 89 | QString _error_msg; 90 | QString _progress; 91 | void goal_response_callback( 92 | rclcpp_action::ClientGoalHandle::SharedPtr); 93 | void feedback_callback( 94 | rclcpp_action::ClientGoalHandle::SharedPtr, 95 | const std::shared_ptr); 96 | void result_callback( 97 | const rclcpp_action::ClientGoalHandle::WrappedResult &); 98 | }; 99 | 100 | 101 | #endif // ROS_QML_PLUGIN__QML_ROSACTION_HPP_ 102 | -------------------------------------------------------------------------------- /src/qml_rosaction.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2024 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #include 16 | 17 | #include 18 | 19 | #include 20 | #include "ros_qml_plugin/qml_rosaction.hpp" 21 | #include "ros_qml_plugin/ros2.hpp" 22 | 23 | using namespace std::chrono_literals; 24 | 25 | 26 | void SetLocaleAction::sendGoal() 27 | { 28 | std::shared_ptr node = Ros2Qml::getInstance().node(); 29 | 30 | if (!_client) { 31 | std::cerr << "Action called without a client." << std::endl; 32 | return; 33 | } 34 | 35 | if (!_client->wait_for_action_server()) { 36 | std::cerr << "Action server not available" << std::endl; 37 | return; 38 | } 39 | 40 | auto goal_msg = i18n_msgs::action::SetLocale::Goal(); 41 | goal_msg.locale = _locale.toStdString(); 42 | 43 | auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); 44 | send_goal_options.goal_response_callback = std::bind( 45 | &SetLocaleAction::goal_response_callback, this, std::placeholders::_1); 46 | send_goal_options.feedback_callback = std::bind( 47 | &SetLocaleAction::feedback_callback, this, 48 | std::placeholders::_1, std::placeholders::_2); 49 | send_goal_options.result_callback = std::bind( 50 | &SetLocaleAction::result_callback, this, std::placeholders::_1); 51 | 52 | auto goal_handle_future = _client->async_send_goal(goal_msg, send_goal_options); 53 | } 54 | 55 | void SetLocaleAction::goal_response_callback( 56 | rclcpp_action::ClientGoalHandle::SharedPtr goal_handle) 57 | { 58 | if (!goal_handle) { 59 | std::cerr << "Goal was rejected by server" << std::endl; 60 | emit goalRejected(); 61 | return; 62 | } 63 | } 64 | 65 | void SetLocaleAction::feedback_callback( 66 | rclcpp_action::ClientGoalHandle::SharedPtr, 67 | const std::shared_ptr feedback) 68 | { 69 | _progress = QString::fromStdString(feedback->progress); 70 | emit feedbackReceived(); 71 | } 72 | 73 | void SetLocaleAction::result_callback( 74 | const rclcpp_action::ClientGoalHandle::WrappedResult & result) 75 | { 76 | switch (result.code) { 77 | case rclcpp_action::ResultCode::SUCCEEDED: 78 | break; 79 | case rclcpp_action::ResultCode::ABORTED: 80 | std::cerr << "Goal was aborted" << std::endl; 81 | return; 82 | case rclcpp_action::ResultCode::CANCELED: 83 | std::cerr << "Goal was canceled" << std::endl; 84 | return; 85 | default: 86 | std::cerr << "Unknown result code" << std::endl; 87 | return; 88 | } 89 | _error_msg = QString::fromStdString(result.result->error_msg); 90 | emit resultReceived(); 91 | } 92 | 93 | template class RosActionImpl; 94 | -------------------------------------------------------------------------------- /src/ros2.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full 3 | // license information. 4 | 5 | #include "ros_qml_plugin/ros2.hpp" 6 | 7 | #include 8 | #include 9 | #include 10 | 11 | Ros2Qml & Ros2Qml::getInstance() 12 | { 13 | static Ros2Qml instance; 14 | return instance; 15 | } 16 | 17 | Ros2Qml::Ros2Qml() {count_wrappers = 0;} 18 | 19 | bool Ros2Qml::isInitialized() const {return context_ != nullptr;} 20 | 21 | void Ros2Qml::init(const QString & name, quint32 options) 22 | { 23 | const QStringList & arguments = QCoreApplication::arguments(); 24 | init(name, arguments, options); 25 | } 26 | 27 | void Ros2Qml::init(const QString & name, const QStringList & argv, quint32) 28 | { 29 | if (context_ != nullptr) { 30 | // TODO(SLE): QML_ROS2_PLUGIN_WARN( 31 | // "Was already initialized. Second call to init ignored."); 32 | return; 33 | } 34 | // std::this_thread::sleep_for(std::chrono::seconds(10)); 35 | int argc = argv.size(); 36 | char ** cargv = new char *[argc]; 37 | for (int i = 0; i < argv.size(); ++i) { 38 | cargv[i] = new char[argv[i].length() + 1]; 39 | std::string string = argv[i].toStdString(); 40 | std::copy(string.begin(), string.end(), cargv[i]); 41 | } 42 | context_ = rclcpp::Context::make_shared(); 43 | context_->init(argc, cargv); // TODO(upstream): init options 44 | rclcpp::NodeOptions node_options; 45 | node_options.context(context_); 46 | node_ = rclcpp::Node::make_shared( 47 | name.toStdString(), 48 | node_options); // TODO(upstream): namespace and init options 49 | 50 | it_ = std::make_shared(node_); 51 | 52 | rclcpp::ExecutorOptions executor_options; 53 | executor_options.context = context_; 54 | auto executor = 55 | rclcpp::executors::SingleThreadedExecutor::make_unique(executor_options); 56 | executor->add_node(node_); 57 | for (int i = 0; i < argv.size(); ++i) { 58 | delete[] cargv[i]; 59 | } 60 | delete[] cargv; 61 | 62 | executor_thread_ = 63 | std::thread([executor = std::move(executor)]() {executor->spin();}); 64 | 65 | emit initialized(); 66 | std::cout << "ROS 2 initialized." << std::endl; 67 | // TODO(SLE): QML_ROS2_PLUGIN_DEBUG("QML Ros2 initialized."); 68 | } 69 | 70 | bool Ros2Qml::ok() const {return rclcpp::ok();} 71 | 72 | void Ros2Qml::registerDependant() {++count_wrappers;} 73 | 74 | void Ros2Qml::unregisterDependant() 75 | { 76 | int count = --count_wrappers; 77 | if (count == 0) { 78 | // TODO(SLE): QML_ROS2_PLUGIN_DEBUG("No dependants left. QML Ros2 shutting 79 | // down."); 80 | rclcpp::shutdown( 81 | context_, "All dependants unregistered, usually that " 82 | "means the application is exiting."); 83 | emit shutdown(); 84 | if (executor_thread_.joinable()) { 85 | executor_thread_.join(); 86 | } 87 | node_.reset(); 88 | context_.reset(); 89 | // TODO(SLE): QML_ROS2_PLUGIN_DEBUG("QML Ros2 shut down."); 90 | } else if (count < 0) { 91 | // TODO(SLE): QML_ROS2_PLUGIN_WARN("Stop spinning was called more often than 92 | // start " 93 | // "spinning! This is a bug!"); 94 | ++count_wrappers; 95 | } 96 | } 97 | 98 | std::shared_ptr Ros2Qml::node() {return node_;} 99 | std::shared_ptr Ros2Qml::image_transport() 100 | { 101 | return it_; 102 | } 103 | -------------------------------------------------------------------------------- /include/ros_qml_plugin/ros_types.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2025 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #ifndef ROS_QML_PLUGIN__ROS_TYPES_HPP_ 16 | #define ROS_QML_PLUGIN__ROS_TYPES_HPP_ 17 | 18 | #include 19 | #include 20 | #include 21 | #include 22 | 23 | class RosPoint 24 | { 25 | Q_GADGET 26 | Q_PROPERTY(QString frame MEMBER _frame) 27 | Q_PROPERTY(double x MEMBER _x) 28 | Q_PROPERTY(double y MEMBER _y) 29 | Q_PROPERTY(double z MEMBER _z) 30 | 31 | public: 32 | RosPoint() {} 33 | RosPoint(const QString & f, double x, double y, double z) 34 | : _frame(f), _x(x), _y(y), _z(z) {} 35 | RosPoint(double x, double y, double z) 36 | : _frame(""), _x(x), _y(y), _z(z) {} 37 | 38 | QString _frame; 39 | double _x; 40 | double _y; 41 | double _z; 42 | 43 | geometry_msgs::msg::PointStamped toMsg() const 44 | { 45 | geometry_msgs::msg::PointStamped point; 46 | point.header.frame_id = _frame.toStdString(); 47 | point.point.x = _x; 48 | point.point.y = _y; 49 | point.point.z = _z; 50 | return point; 51 | } 52 | }; 53 | 54 | Q_DECLARE_METATYPE(RosPoint) 55 | 56 | class RosPose 57 | { 58 | Q_GADGET 59 | Q_PROPERTY(QString frame MEMBER _frame) 60 | Q_PROPERTY(double x MEMBER _x) 61 | Q_PROPERTY(double y MEMBER _y) 62 | Q_PROPERTY(double z MEMBER _z) 63 | Q_PROPERTY(double qx MEMBER _qx) 64 | Q_PROPERTY(double qy MEMBER _qy) 65 | Q_PROPERTY(double qz MEMBER _qz) 66 | Q_PROPERTY(double qw MEMBER _qw) 67 | 68 | public: 69 | RosPose() {} 70 | RosPose(const QString & f, double x, double y, double z) 71 | : _frame(f), _x(x), _y(y), _z(z), _qx(0.0), _qy(0.0), _qz(0.0), _qw(1.0) {} 72 | RosPose(double x, double y, double z) 73 | : _frame(""), _x(x), _y(y), _z(z), _qx(0.0), _qy(0.0), _qz(0.0), _qw(1.0) {} 74 | RosPose( 75 | const QString & f, double x, double y, double z, 76 | double qx, double qy, double qz, double qw) 77 | : _frame(f), _x(x), _y(y), _z(z), _qx(qx), _qy(qy), _qz(qz), _qw(qw) {} 78 | RosPose( 79 | double x, double y, double z, double qx, double qy, double qz, double qw) 80 | : _frame(""), _x(x), _y(y), _z(z), _qx(qx), _qy(qy), _qz(qz), _qw(qw) {} 81 | 82 | QString _frame; 83 | double _x; 84 | double _y; 85 | double _z; 86 | double _qx; 87 | double _qy; 88 | double _qz; 89 | double _qw; 90 | 91 | geometry_msgs::msg::PoseStamped toMsg() const 92 | { 93 | geometry_msgs::msg::PoseStamped pose; 94 | pose.header.frame_id = _frame.toStdString(); 95 | pose.pose.position.x = _x; 96 | pose.pose.position.y = _y; 97 | pose.pose.position.z = _z; 98 | pose.pose.orientation.x = _qx; 99 | pose.pose.orientation.y = _qy; 100 | pose.pose.orientation.z = _qz; 101 | pose.pose.orientation.w = _qw; 102 | 103 | return pose; 104 | } 105 | }; 106 | 107 | Q_DECLARE_METATYPE(RosPose) 108 | 109 | #endif // ROS_QML_PLUGIN__ROS_TYPES_HPP_ 110 | -------------------------------------------------------------------------------- /src/qml_sayskill.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2025 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | 16 | #include 17 | #include 18 | 19 | #include "ros_qml_plugin/qml_sayskill.hpp" 20 | #include "ros_qml_plugin/ros2.hpp" 21 | 22 | 23 | void SaySkill::say(QString input) 24 | { 25 | std::shared_ptr node = Ros2Qml::getInstance().node(); 26 | 27 | if (!_client) { 28 | // if not connected yet, do it now 29 | setAction("/skill/say"); 30 | } 31 | 32 | // if still not conencted, return 33 | if (!_client) { 34 | std::cerr << "Unable to connect to the Say skill." << std::endl; 35 | return; 36 | } 37 | 38 | if (!_client->wait_for_action_server()) { 39 | std::cerr << "Say skill server not available" << std::endl; 40 | } 41 | 42 | auto goal_msg = communication_skills::action::Say::Goal(); 43 | goal_msg.person_id = _person_id.toStdString(); 44 | goal_msg.group_id = _group_id.toStdString(); 45 | goal_msg.input = input.toStdString(); 46 | 47 | auto send_goal_options = 48 | rclcpp_action::Client::SendGoalOptions(); 49 | 50 | send_goal_options.goal_response_callback = std::bind( 51 | &SaySkill::goal_response_callback, this, std::placeholders::_1); 52 | 53 | send_goal_options.feedback_callback = std::bind( 54 | &SaySkill::feedback_callback, this, 55 | std::placeholders::_1, std::placeholders::_2); 56 | 57 | send_goal_options.result_callback = std::bind( 58 | &SaySkill::result_callback, this, std::placeholders::_1); 59 | 60 | auto goal_handle_future = _client->async_send_goal(goal_msg, send_goal_options); 61 | } 62 | 63 | void SaySkill::goal_response_callback( 64 | rclcpp_action::ClientGoalHandle::SharedPtr goal_handle) 65 | { 66 | if (!goal_handle) { 67 | std::cerr << "Goal was rejected by server" << std::endl; 68 | emit goalRejected(); 69 | return; 70 | } 71 | } 72 | 73 | void SaySkill::feedback_callback( 74 | rclcpp_action::ClientGoalHandle::SharedPtr, 75 | const std::shared_ptr) 76 | { 77 | // TODO(SLE): expose feedback data 78 | emit feedbackReceived(); 79 | } 80 | 81 | void SaySkill::result_callback( 82 | const rclcpp_action::ClientGoalHandle::WrappedResult & result) 83 | { 84 | switch (result.code) { 85 | case rclcpp_action::ResultCode::SUCCEEDED: 86 | break; 87 | case rclcpp_action::ResultCode::ABORTED: 88 | std::cerr << "Goal was aborted" << std::endl; 89 | return; 90 | case rclcpp_action::ResultCode::CANCELED: 91 | std::cerr << "Goal was canceled" << std::endl; 92 | return; 93 | default: 94 | std::cerr << "Unknown result code" << std::endl; 95 | return; 96 | } 97 | _error_msg = QString::fromStdString(result.result->result.error_msg); 98 | // TODO(SLE): expose error code 99 | emit resultReceived(); 100 | } 101 | 102 | template class RosActionImpl; 103 | -------------------------------------------------------------------------------- /src/image_provider.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2024 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #include 16 | #include 17 | #include 18 | #include 19 | 20 | #include "image_provider.hpp" 21 | #include "ros_qml_plugin/ros2.hpp" 22 | 23 | using std::placeholders::_1; 24 | 25 | RosImageProvider::RosImageProvider() 26 | : QQuickImageProvider(QQuickImageProvider::Pixmap), 27 | // _it(ros::NodeHandle()), 28 | _last_image(QImage(10, 10, QImage::Format_RGB888)) 29 | { 30 | _last_image.fill(QColor("black").rgba()); 31 | } 32 | 33 | void RosImageProvider::imageCallback( 34 | const sensor_msgs::msg::Image::ConstSharedPtr & msg) 35 | { 36 | if (msg->encoding == "rgb8") { 37 | _last_image = QImage(msg->width, msg->height, QImage::Format_RGB888); 38 | } else if (msg->encoding == "bgr8") { 39 | _last_image = QImage(msg->width, msg->height, QImage::Format_BGR888); 40 | } else if (msg->encoding == "rgba8") { 41 | _last_image = QImage(msg->width, msg->height, QImage::Format_RGBA8888); 42 | } else if (msg->encoding == "mono8") { 43 | _last_image = QImage(msg->width, msg->height, QImage::Format_Grayscale8); 44 | 45 | } else if (msg->encoding == "mono16") { 46 | _last_image = QImage(msg->width, msg->height, QImage::Format_Grayscale16); 47 | } else { 48 | std::cerr << "Unsupported image encoding: " << msg->encoding 49 | << " (supported: rgb8, bgr8, rgba8, mono8, mono16)" << std::endl; 50 | return; 51 | } 52 | 53 | memcpy(_last_image.bits(), msg->data.data(), _last_image.sizeInBytes()); 54 | } 55 | 56 | QImage RosImageProvider::requestImage( 57 | const QString & id, QSize * size, 58 | const QSize & requestedSize) 59 | { 60 | // remove '?' and everything after it, if present 61 | QString topic = id; 62 | int questionMarkIndex = topic.indexOf('?'); 63 | if (questionMarkIndex != -1) { 64 | topic = topic.left(questionMarkIndex); 65 | } 66 | 67 | // if topic does not start with '/', prepend it 68 | if (!topic.startsWith('/')) { 69 | topic.prepend('/'); 70 | } 71 | 72 | 73 | if (_topic != topic.toStdString()) { 74 | _topic = topic.toStdString(); 75 | std::cout << "Subscribing to image topic " << _topic << std::endl; 76 | 77 | auto node = Ros2Qml::getInstance().node(); 78 | 79 | _sub = std::make_shared( 80 | image_transport::create_subscription( 81 | node.get(), 82 | _topic, 83 | std::bind(&RosImageProvider::imageCallback, this, std::placeholders::_1), 84 | "compressed", 85 | rmw_qos_profile_sensor_data 86 | ) 87 | ); 88 | } 89 | 90 | // std::cout << "Image requested" << std::endl; 91 | 92 | QImage result; 93 | 94 | // std::cout << "Last image: " << _last_image.width() << "x" << 95 | // _last_image.height() << ")" << std::endl; 96 | 97 | if (requestedSize.isValid()) { 98 | // std::cout << "(resizing image to " << requestedSize.width() << "x" << 99 | // requestedSize.height() << ")" << std::endl; 100 | result = _last_image.scaled(requestedSize, Qt::KeepAspectRatio); 101 | } else { 102 | // std::cout << "(not resizing image)" << std::endl; 103 | result = _last_image; 104 | } 105 | 106 | *size = result.size(); 107 | return result; 108 | } 109 | -------------------------------------------------------------------------------- /src/qml_navigate_skill.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2025 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | 16 | #include 17 | #include 18 | 19 | #include "ros_qml_plugin/qml_navigate_skill.hpp" 20 | #include "ros_qml_plugin/ros2.hpp" 21 | #include "ros_qml_plugin/ros_types.hpp" 22 | 23 | void NavigateSkill::navigate(const QVariant & target) 24 | { 25 | std::shared_ptr node = Ros2Qml::getInstance().node(); 26 | 27 | if (!_client) { 28 | // if not connected yet, do it now 29 | setAction("/skill/navigate_to_pose"); 30 | } 31 | 32 | // if still not connected, return 33 | if (!_client) { 34 | std::cerr << "Unable to connect to the navigate_to_pose skill." << std::endl; 35 | return; 36 | } 37 | 38 | if (!_client->wait_for_action_server()) { 39 | std::cerr << "navigate_to_pose skill server not available" << std::endl; 40 | } 41 | 42 | auto goal_msg = navigation_skills::action::NavigateToPose::Goal(); 43 | 44 | if (target.canConvert()) { 45 | _pose = target; 46 | goal_msg.pose = _pose.value().toMsg(); 47 | // TODO(SLE): when the navigate skill is ready, 'target' property can be used to pass 48 | // a named target 49 | // } else if (target.canConvert()) { 50 | // _target = target.toString(); 51 | // goal_msg.target = _target.toStdString(); 52 | } else { 53 | qWarning() << "Invalid target type passed to navigate; expected RosPose."; 54 | // qWarning() << "Invalid target type passed to navigate; expected RosPose or QString."; 55 | return; 56 | } 57 | 58 | auto send_goal_options = 59 | rclcpp_action::Client::SendGoalOptions(); 60 | 61 | send_goal_options.goal_response_callback = std::bind( 62 | &NavigateSkill::goal_response_callback, this, std::placeholders::_1); 63 | 64 | send_goal_options.feedback_callback = std::bind( 65 | &NavigateSkill::feedback_callback, this, 66 | std::placeholders::_1, std::placeholders::_2); 67 | 68 | send_goal_options.result_callback = std::bind( 69 | &NavigateSkill::result_callback, this, std::placeholders::_1); 70 | 71 | auto goal_handle_future = _client->async_send_goal(goal_msg, send_goal_options); 72 | } 73 | 74 | void NavigateSkill::goal_response_callback( 75 | rclcpp_action::ClientGoalHandle::SharedPtr goal_handle) 76 | { 77 | if (!goal_handle) { 78 | std::cerr << "Goal was rejected by server" << std::endl; 79 | emit goalRejected(); 80 | return; 81 | } 82 | } 83 | 84 | void NavigateSkill::feedback_callback( 85 | rclcpp_action::ClientGoalHandle::SharedPtr, 86 | const std::shared_ptr) 87 | { 88 | // TODO(SLE): expose feedback data 89 | emit feedbackReceived(); 90 | } 91 | 92 | void NavigateSkill::result_callback( 93 | const rclcpp_action::ClientGoalHandle::WrappedResult & 94 | result) 95 | { 96 | switch (result.code) { 97 | case rclcpp_action::ResultCode::SUCCEEDED: 98 | break; 99 | case rclcpp_action::ResultCode::ABORTED: 100 | std::cerr << "Goal was aborted" << std::endl; 101 | return; 102 | case rclcpp_action::ResultCode::CANCELED: 103 | std::cerr << "Goal was canceled" << std::endl; 104 | return; 105 | default: 106 | std::cerr << "Unknown result code" << std::endl; 107 | return; 108 | } 109 | _error_msg = QString::fromStdString(result.result->result.error_msg); 110 | // TODO(SLE): expose error code 111 | emit resultReceived(); 112 | } 113 | 114 | template class RosActionImpl; 115 | -------------------------------------------------------------------------------- /src/rosplugin.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2024 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | 23 | #include "ros_qml_plugin/ros.hpp" 24 | #include "ros_qml_plugin/ros_types.hpp" 25 | #include "image_provider.hpp" 26 | #include "ros_qml_plugin/qml_rosparam.hpp" 27 | #include "ros_qml_plugin/qml_rossignal.hpp" 28 | #include "ros_qml_plugin/qml_rostopic.hpp" 29 | #include "ros_qml_plugin/qml_rosservice.hpp" 30 | #include "ros_qml_plugin/qml_rosaction.hpp" 31 | #include "ros_qml_plugin/ros2.hpp" 32 | 33 | #include 34 | #include 35 | #include 36 | #include 37 | #include 38 | #include 39 | 40 | #include "ros_qml_plugin/qml_sayskill.hpp" 41 | #include "ros_qml_plugin/qml_chatskill.hpp" 42 | #include "ros_qml_plugin/qml_set_expression_skill.hpp" 43 | #include "ros_qml_plugin/qml_look_at_skill.hpp" 44 | #include "ros_qml_plugin/qml_navigate_skill.hpp" 45 | 46 | class RosPlugin : public QQmlExtensionPlugin 47 | { 48 | Q_OBJECT 49 | Q_PLUGIN_METADATA(IID QQmlExtensionInterface_iid) 50 | 51 | public: 52 | void registerTypes(const char * uri) override 53 | { 54 | Q_ASSERT(uri == QLatin1String("Ros")); 55 | 56 | qRegisterMetaType("RosPoint"); 57 | qRegisterMetaType("RosPose"); 58 | 59 | qmlRegisterSingletonType( 60 | uri, 2, 0, "Ros", [](QQmlEngine * engine, QJSEngine *) -> QObject * { 61 | Q_UNUSED(engine); 62 | return new Ros(); 63 | }); 64 | 65 | qmlRegisterType(uri, 2, 0, "RosParam"); 66 | qmlRegisterType>( 67 | uri, 2, 0, 68 | "StringTopic"); 69 | qmlRegisterType>(uri, 2, 0, "IntTopic"); 70 | qmlRegisterType>(uri, 2, 0, "Int32Topic"); 71 | qmlRegisterType>( 72 | uri, 2, 0, 73 | "FloatTopic"); 74 | qmlRegisterType>(uri, 2, 0, "BoolTopic"); 75 | qmlRegisterType>( 76 | uri, 2, 0, 77 | "ExpressionTopic"); 78 | qmlRegisterType(uri, 2, 0, "ClosedCaptionTopic"); 79 | qmlRegisterType(uri, 2, 0, "LiveSpeechTopic"); 80 | qmlRegisterType(uri, 2, 0, "IntentTopic"); 81 | 82 | qmlRegisterType(uri, 2, 0, "RosSignal"); 83 | 84 | qmlRegisterType(uri, 2, 0, "SetBoolService"); 85 | 86 | qmlRegisterType(uri, 2, 0, "KbSparqlService"); 87 | 88 | qmlRegisterType(uri, 2, 0, "SetUiFragmentService"); 89 | 90 | qmlRegisterType(uri, 2, 0, "GetLocalesService"); 91 | 92 | qmlRegisterType(uri, 2, 0, "SetLocaleAction"); 93 | 94 | qmlRegisterType(uri, 2, 0, "SaySkill"); 95 | qmlRegisterType(uri, 2, 0, "ChatSkill"); 96 | qmlRegisterType(uri, 2, 0, "SetExpressionSkill"); 97 | qmlRegisterType(uri, 2, 0, "LookAtSkill"); 98 | qmlRegisterType(uri, 2, 0, "NavigateSkill"); 99 | } 100 | 101 | void initializeEngine(QQmlEngine * engine, const char * uri) 102 | { 103 | Q_UNUSED(uri); 104 | 105 | QString rosNodeName("qml_ros2_node"); 106 | 107 | std::cout << "Initializing the ROS 2 node" << std::endl; 108 | 109 | QVariant param = engine->rootContext()->contextProperty("ROSNodeName"); 110 | if (param.isValid()) { 111 | rosNodeName = param.toString(); 112 | std::cout << "Node name: " << rosNodeName.toStdString() << std::endl; 113 | } else { 114 | std::cout << "No ROS node name provided, using default: " << rosNodeName.toStdString() 115 | << std::endl; 116 | } 117 | 118 | Ros2Qml::getInstance().init(rosNodeName); 119 | 120 | engine->addImageProvider("rosimage", new RosImageProvider); 121 | } 122 | }; 123 | 124 | #include "rosplugin.moc" 125 | -------------------------------------------------------------------------------- /src/qml_chatskill.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2025 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | 16 | #include 17 | 18 | #include 19 | #include 20 | 21 | #include "ros_qml_plugin/qml_chatskill.hpp" 22 | #include "ros_qml_plugin/ros2.hpp" 23 | 24 | 25 | void ChatSkill::start(QString prompt, QString initial_input) 26 | { 27 | std::shared_ptr node = Ros2Qml::getInstance().node(); 28 | 29 | if (!_client) { 30 | // if not connected yet, do it now 31 | setAction("/skill/chat"); 32 | } 33 | 34 | // if still not conencted, return 35 | if (!_client) { 36 | std::cerr << "Unable to connect to the Chat skill." << std::endl; 37 | return; 38 | } 39 | 40 | if (!_client->wait_for_action_server()) { 41 | std::cerr << "Chat skill server not available" << std::endl; 42 | } 43 | 44 | auto goal_msg = communication_skills::action::Chat::Goal(); 45 | goal_msg.person_id = _person_id.toStdString(); 46 | goal_msg.group_id = _group_id.toStdString(); 47 | 48 | 49 | goal_msg.role.name = "__default__"; 50 | goal_msg.role.configuration = QJsonDocument::fromVariant( 51 | QVariantMap( 52 | { 53 | {"prompt", 54 | prompt}})).toJson().toStdString(); 55 | 56 | if (!initial_input.isEmpty()) { 57 | goal_msg.initiate = true; 58 | goal_msg.initial_input = initial_input.toStdString(); 59 | } 60 | 61 | auto send_goal_options = 62 | rclcpp_action::Client::SendGoalOptions(); 63 | 64 | send_goal_options.goal_response_callback = std::bind( 65 | &ChatSkill::goal_response_callback, this, std::placeholders::_1); 66 | 67 | send_goal_options.feedback_callback = std::bind( 68 | &ChatSkill::feedback_callback, this, 69 | std::placeholders::_1, std::placeholders::_2); 70 | 71 | send_goal_options.result_callback = std::bind( 72 | &ChatSkill::result_callback, this, std::placeholders::_1); 73 | 74 | _goal_handle_future = _client->async_send_goal(goal_msg, send_goal_options); 75 | } 76 | 77 | void ChatSkill::stop() 78 | { 79 | if (!_client) { 80 | std::cerr << "Chat skill client not initialized." << std::endl; 81 | return; 82 | } 83 | 84 | if (!_goal_handle_future.valid()) { 85 | std::cerr << "No active chat to stop." << std::endl; 86 | return; 87 | } 88 | 89 | auto cancel_future = _client->async_cancel_goal(_goal_handle_future.get()); 90 | if (cancel_future.wait_for(std::chrono::seconds(1)) != std::future_status::timeout) { 91 | auto result = cancel_future.get(); 92 | if (result->return_code == action_msgs::srv::CancelGoal::Response::ERROR_NONE) { 93 | std::cout << "Chat canceled successfully." << std::endl; 94 | } else { 95 | std::cerr << "Failed to cancel chat." << std::endl; 96 | } 97 | 98 | } else { 99 | std::cerr << "Chat cancel request timed out." << std::endl; 100 | } 101 | } 102 | 103 | void ChatSkill::goal_response_callback( 104 | rclcpp_action::ClientGoalHandle::SharedPtr goal_handle) 105 | { 106 | if (!goal_handle) { 107 | std::cerr << 108 | "Chat goal was rejected by server! Check the communication_hub logs to know more." << 109 | std::endl; 110 | emit goalRejected(); 111 | return; 112 | } 113 | } 114 | 115 | void ChatSkill::feedback_callback( 116 | rclcpp_action::ClientGoalHandle::SharedPtr, 117 | const std::shared_ptr) 118 | { 119 | // TODO(SLE): expose feedback data 120 | emit feedbackReceived(); 121 | } 122 | 123 | void ChatSkill::result_callback( 124 | const rclcpp_action::ClientGoalHandle::WrappedResult & result) 125 | { 126 | switch (result.code) { 127 | case rclcpp_action::ResultCode::SUCCEEDED: 128 | break; 129 | case rclcpp_action::ResultCode::ABORTED: 130 | std::cerr << "Chat was aborted" << std::endl; 131 | return; 132 | case rclcpp_action::ResultCode::CANCELED: 133 | std::cerr << "Chat was canceled" << std::endl; 134 | return; 135 | default: 136 | std::cerr << "Unknown result code" << std::endl; 137 | return; 138 | } 139 | _error_msg = QString::fromStdString(result.result->result.error_msg); 140 | // TODO(SLE): expose error code 141 | emit resultReceived(); 142 | } 143 | 144 | template class RosActionImpl; 145 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.8) 2 | project(ros_qml_plugin) 3 | set(CMAKE_CXX_STANDARD 14) 4 | 5 | option(GLOBAL_INSTALL "Install the plugin globally instead of as a ROS 2 overlay." OFF) 6 | 7 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 8 | add_compile_options(-Wall -Wextra -Wpedantic) 9 | endif() 10 | 11 | set(CMAKE_INCLUDE_CURRENT_DIR ON) 12 | 13 | set(CMAKE_AUTOUIC ON) 14 | set(CMAKE_AUTOMOC ON) 15 | set(CMAKE_AUTORCC ON) 16 | 17 | # disable warnings for unsafe float comparison generated by Qt's MOC 18 | # code generator 19 | set(DISABLE_PAL_FLAGS true) 20 | 21 | # find dependencies 22 | find_package(ament_cmake_auto REQUIRED) 23 | ament_auto_find_build_dependencies() 24 | 25 | find_package(Qt5Core REQUIRED) 26 | find_package(Qt5Quick REQUIRED) 27 | find_package(Qt5Qml REQUIRED) 28 | find_package(Qt5Multimedia REQUIRED) 29 | 30 | # note: it is *necessary* to include the .hpp in the list of source, 31 | # otherwise the moc will not be generated and the plugin will not be found 32 | set(SOURCES 33 | include/ros_qml_plugin/qml_rosparam.hpp 34 | src/qml_rosparam.cpp 35 | include/ros_qml_plugin/qml_rostopic.hpp 36 | src/qml_rostopic.cpp 37 | include/ros_qml_plugin/qml_rossignal.hpp 38 | src/qml_rossignal.cpp 39 | include/ros_qml_plugin/qml_rosservice.hpp 40 | src/qml_rosservice.cpp 41 | include/ros_qml_plugin/qml_rosaction.hpp 42 | src/qml_rosaction.cpp 43 | include/ros_qml_plugin/qml_look_at_skill.hpp 44 | src/qml_look_at_skill.cpp 45 | include/ros_qml_plugin/qml_sayskill.hpp 46 | src/qml_sayskill.cpp 47 | include/ros_qml_plugin/qml_chatskill.hpp 48 | src/qml_chatskill.cpp 49 | include/ros_qml_plugin/qml_set_expression_skill.hpp 50 | src/qml_set_expression_skill.cpp 51 | include/ros_qml_plugin/qml_navigate_skill.hpp 52 | src/qml_navigate_skill.cpp 53 | include/ros_qml_plugin/qobject_ros2.hpp 54 | include/ros_qml_plugin/ros2.hpp 55 | include/ros_qml_plugin/ros.hpp 56 | include/ros_qml_plugin/ros_types.hpp 57 | src/rosplugin.cpp 58 | src/image_provider.cpp 59 | src/ros2.cpp 60 | src/qobject_ros2.cpp 61 | ) 62 | 63 | add_library(${PROJECT_NAME} SHARED ${SOURCES}) 64 | 65 | target_include_directories(${PROJECT_NAME} PUBLIC 66 | $ 67 | $) 68 | 69 | ament_target_dependencies( 70 | ${PROJECT_NAME} 71 | rclcpp 72 | rclcpp_action 73 | image_transport 74 | std_msgs 75 | hri_msgs 76 | hri_actions_msgs 77 | ui_msgs 78 | i18n_msgs 79 | kb_msgs 80 | std_srvs 81 | communication_skills 82 | interaction_skills 83 | navigation_skills 84 | geometry_msgs 85 | Qt5Core 86 | Qt5Quick 87 | Qt5Qml 88 | Qt5Multimedia 89 | ) 90 | 91 | if(BUILD_TESTING) 92 | find_package(ament_lint_auto REQUIRED) 93 | # the following line skips the linter which checks for copyrights 94 | # comment the line when a copyright and license is added to all source files 95 | set(ament_cmake_copyright_FOUND TRUE) 96 | # the following line skips cpplint (only works in a git repo) 97 | # comment the line when this package is in a git repo and when 98 | # a copyright and license is added to all source files 99 | # set(ament_cmake_cpplint_FOUND TRUE) 100 | ament_lint_auto_find_test_dependencies() 101 | endif() 102 | 103 | ############# 104 | ## Install ## 105 | ############# 106 | 107 | # based on https://github.com/StefanFabian/qml_ros2_plugin/blob/b1f7b9368743d8c146145d0398a5fe3bb34aa870/CMakeLists.txt#L146 108 | 109 | if(${GLOBAL_INSTALL}) 110 | message(STATUS "Installing plugin globally.") 111 | # Install Qml plugin as found here 112 | # https://github.com/4rtzel/cmake-qml-plugin-example/issues/1 113 | set(URI Ros) 114 | string(REPLACE "." "/" TARGETPATH ${URI}) 115 | execute_process(COMMAND qmake -qt5 -query QT_INSTALL_QML 116 | OUTPUT_VARIABLE QT_INSTALL_QML_RAW) 117 | string(REPLACE "\n" "" QT_INSTALL_QML ${QT_INSTALL_QML_RAW}) 118 | if("${QT_INSTALL_QML}" STREQUAL "**Unknown**") 119 | message(FATAL_ERROR "Could not find qml plugin dir. Is qml installed?") 120 | endif() 121 | message(STATUS "Plugin will be installed to ${QT_INSTALL_QML}") 122 | set(DESTDIR "${QT_INSTALL_QML}/${TARGETPATH}") 123 | install(TARGETS ${PROJECT_NAME} DESTINATION ${DESTDIR}) 124 | install(FILES ${CMAKE_CURRENT_LIST_DIR}/qmldir DESTINATION ${DESTDIR}) 125 | else() 126 | message(STATUS "Installing as part of a ROS2 workspace.") 127 | # Register plugin to be found by QML 128 | ament_environment_hooks(rosqmlplugin.dsv.in) 129 | install(TARGETS ${PROJECT_NAME} EXPORT export_${PROJECT_NAME} DESTINATION lib/Ros) 130 | install(FILES qmldir DESTINATION lib/Ros) 131 | # The export is only necessary if part of a ROS2 workspace 132 | ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) 133 | endif() 134 | 135 | 136 | # Following hooks are used to configure the QML2_IMPORT_PATH, so 137 | # that the QML plugin can be found by the QML engine. 138 | ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.dsv.in") 139 | ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.sh.in") 140 | 141 | ament_package() 142 | -------------------------------------------------------------------------------- /src/qml_look_at_skill.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2025 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | 16 | #include 17 | 18 | #include "ros_qml_plugin/qml_look_at_skill.hpp" 19 | #include "ros_qml_plugin/ros2.hpp" 20 | #include "ros_qml_plugin/ros_types.hpp" 21 | 22 | 23 | void LookAtSkill::look_at(QVariant v_target, const QString & policy) 24 | { 25 | using namespace std::placeholders; 26 | 27 | 28 | std::shared_ptr node = Ros2Qml::getInstance().node(); 29 | 30 | if (!_client) { 31 | // if not connected yet, do it now 32 | setAction("/skill/look_at"); 33 | } 34 | 35 | // if still not connected, return 36 | if (!_client) { 37 | std::cerr << "Unable to connect to the LookAt skill." << std::endl; 38 | return; 39 | } 40 | 41 | if (!_client->wait_for_action_server()) { 42 | std::cerr << "LookAt skill server not available" << std::endl; 43 | } 44 | 45 | auto goal_msg = interaction_skills::action::LookAt::Goal(); 46 | goal_msg.policy = policy.toStdString(); 47 | 48 | // v_target invalid means that no target is set, which is fine (some 49 | // policies do not require a target) 50 | if (v_target.isValid()) { 51 | if (v_target.canConvert()) { 52 | RosPoint target = v_target.value(); 53 | goal_msg.target = target.toMsg(); 54 | } else { 55 | qWarning() << "Invalid point type passed look_at"; 56 | return; 57 | } 58 | } 59 | 60 | auto send_goal_options = 61 | rclcpp_action::Client::SendGoalOptions(); 62 | 63 | send_goal_options.goal_response_callback = std::bind( 64 | &LookAtSkill::goal_response_callback, this, _1); 65 | 66 | send_goal_options.feedback_callback = std::bind( 67 | &LookAtSkill::feedback_callback, this, _1, _2); 68 | 69 | send_goal_options.result_callback = std::bind( 70 | &LookAtSkill::result_callback, this, _1); 71 | 72 | if (v_target.isValid()) { 73 | if (!policy.isEmpty()) { 74 | qInfo() << "Sending LookAt goal with policy " << policy << " and target <" << 75 | goal_msg.target.point.x << ", " << 76 | goal_msg.target.point.y << ", " << goal_msg.target.point.z << "> in " << 77 | QString::fromStdString(goal_msg.target.header.frame_id); 78 | } else { 79 | qInfo() << "Sending LookAt goal to track <" << goal_msg.target.point.x << ", " << 80 | goal_msg.target.point.y << ", " << goal_msg.target.point.z << "> in " << 81 | QString::fromStdString(goal_msg.target.header.frame_id); 82 | } 83 | } else { 84 | qInfo() << "Sending LookAt goal with policy " << policy << " (no target frame)"; 85 | } 86 | auto goal_handle_future = _client->async_send_goal(goal_msg, send_goal_options); 87 | } 88 | 89 | void LookAtSkill::glance(QVariant target) 90 | { 91 | look_at( 92 | target, 93 | QString::fromStdString(interaction_skills::action::LookAt::Goal::GLANCE)); 94 | } 95 | 96 | void LookAtSkill::look_at_faces() 97 | { 98 | look_at( 99 | QVariant(), 100 | QString::fromStdString(interaction_skills::action::LookAt::Goal::SOCIAL)); 101 | } 102 | 103 | void LookAtSkill::look_around_randomly() 104 | { 105 | look_at( 106 | QVariant(), 107 | QString::fromStdString(interaction_skills::action::LookAt::Goal::RANDOM)); 108 | } 109 | 110 | void LookAtSkill::reset() 111 | { 112 | look_at( 113 | QVariant(), 114 | QString::fromStdString(interaction_skills::action::LookAt::Goal::RESET)); 115 | } 116 | 117 | 118 | void LookAtSkill::goal_response_callback( 119 | rclcpp_action::ClientGoalHandle::SharedPtr goal_handle) 120 | { 121 | if (!goal_handle) { 122 | std::cerr << "Goal was rejected by server" << std::endl; 123 | emit goalRejected(); 124 | return; 125 | } 126 | } 127 | 128 | void LookAtSkill::feedback_callback( 129 | rclcpp_action::ClientGoalHandle::SharedPtr, 130 | const std::shared_ptr) 131 | { 132 | // TODO(SLE): expose feedback data 133 | emit feedbackReceived(); 134 | } 135 | 136 | void LookAtSkill::result_callback( 137 | const rclcpp_action::ClientGoalHandle::WrappedResult & 138 | result) 139 | { 140 | switch (result.code) { 141 | case rclcpp_action::ResultCode::SUCCEEDED: 142 | break; 143 | case rclcpp_action::ResultCode::ABORTED: 144 | std::cerr << "Goal was aborted" << std::endl; 145 | return; 146 | case rclcpp_action::ResultCode::CANCELED: 147 | std::cerr << "Goal was canceled" << std::endl; 148 | return; 149 | default: 150 | std::cerr << "Unknown result code" << std::endl; 151 | return; 152 | } 153 | _error_msg = QString::fromStdString(result.result->result.error_msg); 154 | // TODO(SLE): expose error code 155 | emit resultReceived(); 156 | } 157 | 158 | template class RosActionImpl; 159 | -------------------------------------------------------------------------------- /include/ros_qml_plugin/qml_rosservice.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2024 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #ifndef ROS_QML_PLUGIN__QML_ROSSERVICE_HPP_ 16 | #define ROS_QML_PLUGIN__QML_ROSSERVICE_HPP_ 17 | 18 | #include 19 | #include 20 | 21 | #include 22 | 23 | #include 24 | #include 25 | #include 26 | #include 27 | #include 28 | 29 | #include "ros_qml_plugin/qobject_ros2.hpp" 30 | 31 | class RosService : public QObjectRos2 32 | { 33 | Q_OBJECT 34 | Q_PROPERTY(QString service WRITE setService MEMBER _service_name) 35 | 36 | public: 37 | RosService() {} 38 | virtual ~RosService() {} 39 | 40 | virtual void setService(const QString &) = 0; 41 | 42 | signals: 43 | void requestReceived(); 44 | 45 | protected: 46 | QString _service_name; 47 | }; 48 | 49 | template 50 | class RosServiceImpl : public RosService 51 | { 52 | public: 53 | RosServiceImpl() {} 54 | virtual ~RosServiceImpl() {} 55 | 56 | void setService(const QString &); 57 | 58 | protected: 59 | virtual void handle_request( 60 | const std::shared_ptr, 61 | std::shared_ptr) {} 62 | 63 | typename rclcpp::Service::SharedPtr _service; 64 | // rclcpp::CallbackGroup::SharedPtr _cb_group; 65 | }; 66 | 67 | /////////////////////////////////////////////////////////////////////////////// 68 | 69 | class RosServiceClient : public QObjectRos2 70 | { 71 | Q_OBJECT 72 | Q_PROPERTY(QString service WRITE setService MEMBER _service_name) 73 | 74 | public: 75 | RosServiceClient() {} 76 | virtual ~RosServiceClient() {} 77 | 78 | virtual void setService(const QString &) = 0; 79 | 80 | signals: 81 | void resultReceived(); 82 | 83 | protected: 84 | QString _service_name; 85 | }; 86 | 87 | template 88 | class RosServiceClientImpl : public RosServiceClient 89 | { 90 | public: 91 | RosServiceClientImpl() {} 92 | virtual ~RosServiceClientImpl() {} 93 | 94 | void setService(const QString &); 95 | 96 | protected: 97 | typename rclcpp::Client::SharedPtr _client; 98 | // rclcpp::CallbackGroup::SharedPtr _cb_group; 99 | }; 100 | 101 | 102 | /////////////////////////////////////////////////////////////////////////////// 103 | 104 | class SetBoolService : public RosServiceImpl 105 | { 106 | Q_OBJECT 107 | Q_PROPERTY(bool value MEMBER _value NOTIFY valueChanged) 108 | 109 | signals: 110 | void valueChanged(); 111 | 112 | private: 113 | bool _value; 114 | 115 | void handle_request( 116 | const std::shared_ptr request, 117 | std::shared_ptr response) override; 118 | }; 119 | 120 | /////////////////////////////////////////////////////////////////////////////// 121 | 122 | class GetLocalesService : public RosServiceClientImpl 123 | { 124 | Q_OBJECT 125 | Q_PROPERTY(QStringList locales MEMBER _locales) 126 | 127 | public: 128 | Q_INVOKABLE void callService(); 129 | 130 | private: 131 | QStringList _locales; 132 | void handle_response(rclcpp::Client::SharedFuture future); 133 | }; 134 | 135 | /////////////////////////////////////////////////////////////////////////////// 136 | 137 | class KbSparqlService : public RosServiceClientImpl 138 | { 139 | Q_OBJECT 140 | Q_PROPERTY(QString query WRITE setQuery READ getQuery NOTIFY queryChanged) 141 | Q_PROPERTY(QVariant value READ getValue NOTIFY valueChanged) 142 | 143 | signals: 144 | void queryChanged(); 145 | void valueChanged(); 146 | void errorOccurred(const QString & message); 147 | 148 | public: 149 | void setQuery(const QString & query) 150 | { 151 | if (query != _query) { 152 | _query = query; 153 | emit queryChanged(); 154 | } 155 | } 156 | QString getQuery() const 157 | { 158 | return _query; 159 | } 160 | QVariant getValue() const 161 | { 162 | return _value; 163 | } 164 | 165 | Q_INVOKABLE void executeQuery(); 166 | 167 | private: 168 | QString _query = ""; 169 | QVariant _value = QVariant(QVariantMap()); 170 | 171 | void handle_response(rclcpp::Client::SharedFuture future); 172 | }; 173 | 174 | /////////////////////////////////////////////////////////////////////////////// 175 | 176 | class SetUiFragmentService : public RosServiceImpl 177 | { 178 | Q_OBJECT 179 | Q_PROPERTY(QString qml_import_path MEMBER _qml_import_path) 180 | Q_PROPERTY(QString qml_fragment MEMBER _qml_fragment) 181 | 182 | private: 183 | QString _qml_import_path; 184 | QString _qml_fragment; 185 | 186 | void handle_request( 187 | const std::shared_ptr request, 188 | std::shared_ptr response) override; 189 | }; 190 | 191 | 192 | #endif // ROS_QML_PLUGIN__QML_ROSSERVICE_HPP_ 193 | -------------------------------------------------------------------------------- /src/qml_rosservice.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2024 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | 21 | #include "ros_qml_plugin/qml_rosservice.hpp" 22 | #include "ros_qml_plugin/ros2.hpp" 23 | 24 | using namespace std::chrono_literals; 25 | 26 | template void RosServiceImpl::setService(const QString & service) 27 | { 28 | if (service == _service_name) { 29 | return; 30 | } 31 | 32 | std::shared_ptr node = Ros2Qml::getInstance().node(); 33 | 34 | _service = node->create_service( 35 | service.toStdString(), std::bind( 36 | &RosServiceImpl::handle_request, this, 37 | std::placeholders::_1, std::placeholders::_2), rmw_qos_profile_services_default); 38 | } 39 | 40 | 41 | /////////////////////////////////////////////////////////////////////////////// 42 | 43 | template void RosServiceClientImpl::setService(const QString & service) 44 | { 45 | if (service == _service_name) { 46 | return; 47 | } 48 | 49 | std::shared_ptr node = Ros2Qml::getInstance().node(); 50 | 51 | _client = node->create_client( 52 | service.toStdString(), rmw_qos_profile_services_default); 53 | } 54 | 55 | /////////////////////////////////////////////////////////////////////////////// 56 | 57 | void SetBoolService::handle_request( 58 | const std::shared_ptr request, 59 | std::shared_ptr response) 60 | { 61 | emit requestReceived(); 62 | bool value = request->data; 63 | if (value != _value) { 64 | _value = value; 65 | emit valueChanged(); 66 | } 67 | response->success = true; 68 | } 69 | 70 | template class RosServiceImpl; 71 | 72 | /////////////////////////////////////////////////////////////////////////////// 73 | 74 | void GetLocalesService::callService() 75 | { 76 | std::shared_ptr node = Ros2Qml::getInstance().node(); 77 | 78 | if (!_client) { 79 | std::cerr << "Service called without a client." << std::endl; 80 | return; 81 | } 82 | 83 | if (!_client->service_is_ready()) { 84 | std::cerr << "Service not available" << std::endl; 85 | return; 86 | } 87 | 88 | auto request = std::make_shared(); 89 | auto result_future = 90 | _client->async_send_request( 91 | request, 92 | std::bind(&GetLocalesService::handle_response, this, std::placeholders::_1)); 93 | } 94 | 95 | void GetLocalesService::handle_response( 96 | rclcpp::Client::SharedFuture future) 97 | { 98 | QStringList locales; 99 | auto result_locales = future.get()->locales; 100 | for (const auto & locale : result_locales) { 101 | locales.append(QString::fromStdString(locale)); 102 | } 103 | if (locales != _locales) { 104 | _locales = locales; 105 | } 106 | emit resultReceived(); 107 | } 108 | 109 | template class RosServiceClientImpl; 110 | 111 | /////////////////////////////////////////////////////////////////////////////// 112 | 113 | void KbSparqlService::executeQuery() 114 | { 115 | std::shared_ptr node = Ros2Qml::getInstance().node(); 116 | 117 | if (!_client) { 118 | std::cerr << "Service called without a client." << std::endl; 119 | return; 120 | } 121 | 122 | if (!_client->service_is_ready()) { 123 | std::cerr << "Service not available" << std::endl; 124 | return; 125 | } 126 | 127 | if (_query.isEmpty()) { 128 | std::cerr << "Query is empty" << std::endl; 129 | return; 130 | } 131 | 132 | auto request = std::make_shared(); 133 | request->query = _query.toStdString(); 134 | 135 | // clear previous value 136 | _value = QVariant(QVariantMap()); 137 | emit valueChanged(); 138 | 139 | auto result_future = 140 | _client->async_send_request( 141 | request, 142 | std::bind(&KbSparqlService::handle_response, this, std::placeholders::_1)); 143 | } 144 | 145 | void KbSparqlService::handle_response( 146 | rclcpp::Client::SharedFuture future) 147 | { 148 | auto ok = future.get()->success; 149 | 150 | if (ok) { 151 | auto result = future.get()->json; 152 | QJsonDocument doc = QJsonDocument::fromJson(QString::fromStdString(result).toUtf8()); 153 | _value = doc.toVariant(); 154 | emit valueChanged(); 155 | } else { 156 | QString error_msg = QString::fromStdString(future.get()->error_msg); 157 | emit errorOccurred(error_msg); 158 | } 159 | 160 | emit resultReceived(); 161 | } 162 | 163 | template class RosServiceClientImpl; 164 | 165 | 166 | /////////////////////////////////////////////////////////////////////////////// 167 | 168 | 169 | void SetUiFragmentService::handle_request( 170 | const std::shared_ptr request, 171 | std::shared_ptr response) 172 | { 173 | _qml_import_path = QString::fromStdString(request->qml_import_path); 174 | _qml_fragment = QString::fromStdString(request->qml_fragment); 175 | 176 | // inject the new import path 177 | if (!_qml_import_path.isEmpty()) { 178 | if (!QQmlEngine::contextForObject(this)) { 179 | std::cerr << "No QQmlEngine context for object" << std::endl; 180 | return; 181 | } 182 | 183 | std::cout << "Adding qml import path:" << _qml_import_path.toStdString() << std::endl; 184 | QQmlEngine::contextForObject(this)->engine()->addImportPath( 185 | _qml_import_path); 186 | } 187 | 188 | response->error_msg = "success"; 189 | 190 | emit requestReceived(); 191 | } 192 | 193 | template class RosServiceImpl; 194 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | ROS 2 QML plugin 2 | ================ 3 | 4 | ![Screenshot of the sample app](doc/screenshot-sample-app.png) 5 | 6 | Requirements 7 | ------------ 8 | 9 | - `qt5`. On Debian/Ubuntu: `apt install qmake qt5-default qtdeclarative5-dev` 10 | - ROS (tested with ROS humble. Check the `master` branch for kinectic and noetic support). 11 | 12 | *Note that this has only been tested on Linux, and would likely require 13 | significant work to get it to work on a different operating system.* 14 | 15 | Installation 16 | ------------ 17 | 18 | You can install the plugin as any ROS 2 package, using `colcon`. 19 | If you then source your ROS 2 environment, any qml application will be able to 20 | use the plugin. 21 | 22 | To compile: 23 | 24 | ```bash 25 | > rosdep install --from-paths src --ignore-src -y # install dependencies 26 | > colcon build --packages-select ros_qml_plugin 27 | ``` 28 | 29 | General Usage 30 | ------------- 31 | 32 | **Important: always launch QtCreator from the command-line! otherwise, your ROS 33 | configuration will not be set up, and QtCreator won't find the ROS libraries.** 34 | 35 | In your QML files, import `Ros 2.0`: 36 | 37 | ```qml 38 | 39 | import Ros 2.0 40 | ``` 41 | 42 | By default, the plugin creates a ROS node with the name `qml_ros2_node`. You can 43 | change this by setting the `ROSNodeName` property in the QML context: 44 | 45 | ```cpp 46 | QQmlApplicationEngine engine; 47 | 48 | QString rosNodeName = "robot_head_display"; 49 | engine.rootContext()->setContextProperty("ROSNodeName", rosNodeName); 50 | ``` 51 | 52 | ### Working 'Hello World' example 53 | 54 | This example creates a blank window. If you click anywhere onto the window, the 55 | string `Hello world` is published on the topic `/hello`: 56 | 57 | ```qml 58 | import QtQuick 2.12 59 | import QtQuick.Window 2.12 60 | 61 | import Ros 2.0 62 | 63 | Window { 64 | visible: true 65 | width: 640 66 | height: 480 67 | title: qsTr("Hello World") 68 | 69 | StringTopic{ 70 | id: hello_publisher 71 | topic: "hello" 72 | 73 | } 74 | 75 | MouseArea { 76 | anchors.fill: parent 77 | onClicked: { 78 | hello_publisher.value = "Hello world" 79 | } 80 | 81 | } 82 | 83 | } 84 | ``` 85 | 86 | Supported ROS features 87 | ---------------------- 88 | 89 | Check [sample.qml](examples/sample.qml) for a complete example. 90 | You can actually test it by running `qmlscene examples/sample.qml` (cf 91 | screenshot above). 92 | 93 | Supports: 94 | 95 | - [displaying a ROS image topic](#displaying-ros-image-topics) 96 | - setting/reading ROS 2 parameters (`RosParam`) of basic type (string, int, 97 | float, bool). You must set the property `name` to the parameter name. If you 98 | also set the `node` property, the parameter will be set on that node, 99 | otherwise it will be set on the QML node itself. 100 | - bi-directional event signaling (``RosSignal``) by sending an `Empty` message 101 | on a specfic topic 102 | - publish and subscribe to string, int16, int32, float32 and bool topics 103 | (`StringTopic`, `IntTopic`, `Int32Topic`, `FloatTopic`, `BoolTopic`). 104 | To publish, set the `value` property. To subscribe, use the `onMessageReceived` signal. 105 | - Create a `SetBool` service (`SetBoolService`) 106 | 107 | #### Forcing a topic direction 108 | 109 | By default, ROS topic are created as bidirectional. You can force a topic to be 110 | either a publisher or a subscriber by setting the `isPublisher` and 111 | `isSubscriber` boolean properties (both are `true` by default). 112 | 113 | For instance, the value of `hello_publisher` will be published on the topic 114 | `/hello`, but will never be overwritten by a message received on the same topic: 115 | 116 | ```qml 117 | StringTopic{ 118 | id: hello_publisher 119 | topic: "/hello" 120 | value: "Hello world" 121 | isSubscriber: false 122 | } 123 | ``` 124 | 125 | ### Skills 126 | 127 | Supported skills: 128 | 129 | - `SaySkill`: a skill that can be used to make the robot say something. 130 | 131 | Example: 132 | ```qml 133 | SaySkill { 134 | id: skill 135 | } 136 | skill.say("Hello world") 137 | ``` 138 | - `ChatSkill`: a skill that can be used to initiate a chat with a user. 139 | 140 | Example: 141 | ```qml 142 | SaySkill { 143 | id: skill 144 | } 145 | skill.start("You are an helpful robot assistant", "Hello! How can I help?") // first the chatbot prompt, then the initial speech. Both can be omitted 146 | skill.stop() // to end the dialogue 147 | ``` 148 | - `SetExpression`: a skill that can be used to set an expression on the robot. 149 | 150 | Example: 151 | ```qml 152 | SetExpression { 153 | id: skill 154 | } 155 | skill.set_expression("happy") 156 | skill.set_expression(0.7, -0.4) // using valence and arousal values 157 | ``` 158 | - `LookAtSkill`: a skill that can be used to make the robot look at a specific point in space. 159 | 160 | Example: 161 | ```qml 162 | LookAtSkill { 163 | id: skill 164 | } 165 | skill.look_at(Ros.point("base_link", 1.0, 0.0, 0.0)) 166 | skill.look_at_faces() 167 | skill.look_around_randomly() 168 | skill.glance(Ros.point("base_link", 1.0, 0.0, 0.0), 1000) // glance at a point for 2 second 169 | skill.reset() // look straight ahead 170 | ``` 171 | 172 | - `NavigateSkill`: a skill that makes mobile platform to move to a specific 173 | pose in the world. 174 | 175 | Example: 176 | ```qml 177 | NavigateSkill { 178 | id: skill 179 | } 180 | skill.navigate(Ros.pose("map", 1.0, 0.0, 0.0, 0.0, 0.0, 0.71, 0.71)) // x,y,z, qx, qy, qz, qw -> here a 90deg rotation around Z 181 | skill.navigate(Ros.pose("map", 1.0, 0.0, 0.0)) // using only the position 182 | skill.navigate(Ros.pose(1.0, 0.0, 0.0)) // relative to the robot itself 183 | ``` 184 | 185 | ### Live speech 186 | 187 | The `LiveSpeechTopic` QML object can be used to either listen to incoming ASR results, or fake 188 | speech recognition by publishing a `value`. The API is compatible with the ROS4HRI standard. 189 | 190 | ```qml 191 | import Ros 2.0 192 | LiveSpeechTopic { 193 | id: live_speech 194 | speaker_name: "joe" // by default, 'anonymous_speaker' 195 | onMessageReceived: { 196 | console.log("ASR result: " + message) 197 | } 198 | } 199 | MouseArea { 200 | anchors.fill: parent 201 | onClicked: { 202 | live_speech.value = "Hello world" 203 | } 204 | } 205 | ``` 206 | 207 | ### Displaying ROS image topics 208 | 209 | This uses a special QML ``ImageProvider`` to read images from a ROS topic. Specify the topic using: `img.source = "image://rosimage/"`. 210 | 211 | Typical usage, that refreshes the image at 20Hz: 212 | 213 | ```qml 214 | import Ros 2.0 215 | 216 | Image { 217 | id: img 218 | cache: false 219 | 220 | property int counter: 0 221 | anchors.fill: parent 222 | source: "image://rosimage/v4l/camera/image_raw?" + counter.toString() 223 | 224 | Timer { 225 | interval: 50 226 | repeat: true 227 | running: parent.visible 228 | onTriggered: parent.counter += 1 229 | } 230 | } 231 | ``` 232 | 233 | note that only a limited set of image formats are supported (`rgb888`, `bgr888`, `rgba8888`, `mono8`, `mono16`). 234 | 235 | 236 | 237 | Similar projects 238 | ---------------- 239 | 240 | - https://github.com/StefanFabian/qml_ros2_plugin: similar project, with a focus 241 | on lower-level access to ROS 2 topics, actions, services. More generic, but 242 | slightly more complex to use. 243 | 244 | -------------------------------------------------------------------------------- /include/ros_qml_plugin/qml_rostopic.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2024 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #ifndef ROS_QML_PLUGIN__QML_ROSTOPIC_HPP_ 16 | #define ROS_QML_PLUGIN__QML_ROSTOPIC_HPP_ 17 | 18 | #include 19 | #include 20 | #include 21 | #include 22 | #include 23 | 24 | #include 25 | #include 26 | #include 27 | #include 28 | #include 29 | 30 | #include "ros_qml_plugin/qobject_ros2.hpp" 31 | 32 | #define SHARED_CONSTANT(type, name, value) \ 33 | Q_PROPERTY(type name READ name CONSTANT) \ 34 | type name() const {return value;} 35 | 36 | 37 | /////////////////////////////////////////////////////////////////////////////// 38 | /** 39 | * @brief A QtQuick item that publish/subscribe to a ROS2 topic of type 40 | * std_msgs/Int16. 41 | */ 42 | class RosTopic : public QObjectRos2 43 | { 44 | Q_OBJECT 45 | Q_PROPERTY(QVariant value WRITE setValue MEMBER _value NOTIFY onValueChanged) 46 | Q_PROPERTY(QString topic WRITE setTopic MEMBER _topic) 47 | Q_PROPERTY(bool isPublisher WRITE setIsPublisher MEMBER _is_publisher) 48 | Q_PROPERTY(bool isSubscriber WRITE setIsSubscriber MEMBER _is_subscriber) 49 | 50 | public: 51 | RosTopic() {} 52 | virtual ~RosTopic() {} 53 | 54 | virtual void setTopic(const QString &) = 0; 55 | virtual void setValue(const QVariant &) = 0; 56 | virtual void setIsPublisher(const bool &) = 0; 57 | virtual void setIsSubscriber(const bool &) = 0; 58 | Q_INVOKABLE void publish() {} 59 | 60 | signals: 61 | void onValueChanged(); 62 | void messageReceived(); 63 | 64 | protected: 65 | QString _topic; 66 | QVariant _value; 67 | 68 | // by default, a RosTopic is both a publisher and a subscriber 69 | bool _is_publisher = true; 70 | bool _is_subscriber = true; 71 | }; 72 | 73 | /////////////////////////////////////////////////////////////////////////////// 74 | template 75 | class RosTopicImpl : public RosTopic 76 | { 77 | public: 78 | RosTopicImpl() {} 79 | virtual ~RosTopicImpl() {} 80 | 81 | void setTopic(const QString &); 82 | void setValue(const QVariant &); 83 | void setIsPublisher(const bool &); 84 | void setIsSubscriber(const bool &); 85 | Q_INVOKABLE void publish(); 86 | 87 | protected: 88 | virtual void onIncomingData(const T & data); 89 | 90 | typename rclcpp::Publisher::SharedPtr _publisher; 91 | typename rclcpp::Subscription::SharedPtr _subscriber; 92 | }; 93 | 94 | /////////////////////////////////////////////////////////////////////////////// 95 | class ClosedCaptionTopic 96 | : public RosTopicImpl 97 | { 98 | Q_OBJECT 99 | Q_PROPERTY(QString speaker_id MEMBER _speaker_id) 100 | 101 | protected: 102 | void 103 | onIncomingData(const hri_actions_msgs::msg::ClosedCaption & data) override; 104 | 105 | private: 106 | QString _speaker_id; 107 | }; 108 | 109 | /////////////////////////////////////////////////////////////////////////////// 110 | class LiveSpeechTopic 111 | : public RosTopicImpl 112 | { 113 | Q_OBJECT 114 | Q_PROPERTY(QString speaker_name WRITE setSpeakerName MEMBER _speaker_name) 115 | Q_PROPERTY( 116 | QString incremental MEMBER _incremental NOTIFY onIncrementalChanged) 117 | Q_PROPERTY(double confidence MEMBER _confidence) 118 | Q_PROPERTY(QString locale MEMBER _locale) 119 | 120 | public: 121 | void setSpeakerName(const QString &); 122 | 123 | Q_INVOKABLE void publish(); 124 | 125 | signals: 126 | void onIncrementalChanged(); 127 | 128 | protected: 129 | void 130 | onIncomingData(const hri_msgs::msg::LiveSpeech & data) override; 131 | 132 | private: 133 | typename rclcpp::Publisher::SharedPtr _user_id_publisher; 134 | 135 | QString _speaker_name; 136 | QString _incremental; 137 | double _confidence = 0.0; 138 | QString _locale; 139 | }; 140 | 141 | /////////////////////////////////////////////////////////////////////////////// 142 | class IntentTopic 143 | : public RosTopicImpl 144 | { 145 | Q_OBJECT 146 | Q_PROPERTY(QString data MEMBER _data) 147 | 148 | // intents 149 | SHARED_CONSTANT( 150 | QString, WakeUp, 151 | QString::fromStdString(hri_actions_msgs::msg::Intent::WAKEUP)) 152 | SHARED_CONSTANT( 153 | QString, Suspend, 154 | QString::fromStdString(hri_actions_msgs::msg::Intent::SUSPEND)) 155 | SHARED_CONSTANT( 156 | QString, RawUserInput, 157 | QString::fromStdString(hri_actions_msgs::msg::Intent::RAW_USER_INPUT)) 158 | SHARED_CONSTANT( 159 | QString, EngageWith, 160 | QString::fromStdString(hri_actions_msgs::msg::Intent::ENGAGE_WITH)) 161 | SHARED_CONSTANT( 162 | QString, Guide, 163 | QString::fromStdString(hri_actions_msgs::msg::Intent::GUIDE)) 164 | SHARED_CONSTANT( 165 | QString, GrabObject, 166 | QString::fromStdString(hri_actions_msgs::msg::Intent::GRAB_OBJECT)) 167 | SHARED_CONSTANT( 168 | QString, BringObject, 169 | QString::fromStdString(hri_actions_msgs::msg::Intent::BRING_OBJECT)) 170 | SHARED_CONSTANT( 171 | QString, PlaceObject, 172 | QString::fromStdString(hri_actions_msgs::msg::Intent::PLACE_OBJECT)) 173 | SHARED_CONSTANT( 174 | QString, Greet, 175 | QString::fromStdString(hri_actions_msgs::msg::Intent::GREET)) 176 | SHARED_CONSTANT( 177 | QString, Say, 178 | QString::fromStdString(hri_actions_msgs::msg::Intent::SAY)) 179 | SHARED_CONSTANT( 180 | QString, PresentContent, 181 | QString::fromStdString(hri_actions_msgs::msg::Intent::PRESENT_CONTENT)) 182 | SHARED_CONSTANT( 183 | QString, PerformMotion, 184 | QString::fromStdString(hri_actions_msgs::msg::Intent::PERFORM_MOTION)) 185 | SHARED_CONSTANT( 186 | QString, StartActivity, 187 | QString::fromStdString(hri_actions_msgs::msg::Intent::START_ACTIVITY)) 188 | SHARED_CONSTANT( 189 | QString, StopActivity, 190 | QString::fromStdString(hri_actions_msgs::msg::Intent::STOP_ACTIVITY)) 191 | 192 | // modalities 193 | Q_PROPERTY(QString modality MEMBER _modality) 194 | SHARED_CONSTANT( 195 | QString, ModalityTouchscreen, 196 | QString::fromStdString(hri_actions_msgs::msg::Intent::MODALITY_TOUCHSCREEN)) 197 | SHARED_CONSTANT( 198 | QString, ModalitySpeech, 199 | QString::fromStdString(hri_actions_msgs::msg::Intent::MODALITY_SPEECH)) 200 | SHARED_CONSTANT( 201 | QString, ModalityMotion, 202 | QString::fromStdString(hri_actions_msgs::msg::Intent::MODALITY_MOTION)) 203 | SHARED_CONSTANT( 204 | QString, ModalityOther, 205 | QString::fromStdString(hri_actions_msgs::msg::Intent::MODALITY_OTHER)) 206 | SHARED_CONSTANT( 207 | QString, ModalityInternal, 208 | QString::fromStdString(hri_actions_msgs::msg::Intent::MODALITY_INTERNAL)) 209 | 210 | // source 211 | Q_PROPERTY(QString source MEMBER _source) 212 | SHARED_CONSTANT( 213 | QString, SourceRobotItself, 214 | QString::fromStdString(hri_actions_msgs::msg::Intent::ROBOT_ITSELF)) 215 | SHARED_CONSTANT( 216 | QString, SourceRemoteSupervisor, 217 | QString::fromStdString(hri_actions_msgs::msg::Intent::REMOTE_SUPERVISOR)) 218 | SHARED_CONSTANT( 219 | QString, SourceUnknownAgent, 220 | QString::fromStdString(hri_actions_msgs::msg::Intent::UNKNOWN_AGENT)) 221 | SHARED_CONSTANT( 222 | QString, SourceUnknown, 223 | QString::fromStdString(hri_actions_msgs::msg::Intent::UNKNOWN)) 224 | 225 | public: 226 | Q_INVOKABLE void publish(); 227 | 228 | protected: 229 | void 230 | onIncomingData(const hri_actions_msgs::msg::Intent & data) override; 231 | 232 | private: 233 | QString _data; 234 | QString _modality; 235 | QString _source; 236 | }; 237 | 238 | 239 | #endif // ROS_QML_PLUGIN__QML_ROSTOPIC_HPP_ 240 | -------------------------------------------------------------------------------- /CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package ros_qml_plugin 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 2.22.0 (2025-12-09) 6 | ------------------- 7 | * add a KbSparqlService to execute SPARQL queries to a knowledge base 8 | * Contributors: Séverin Lemaignan 9 | 10 | 2.21.7 (2025-09-22) 11 | ------------------- 12 | * remove unnecessary ros2::ok checks 13 | Those checks actually randomly failed, for unknown reason 14 | * Contributors: Séverin Lemaignan 15 | 16 | 2.21.6 (2025-08-29) 17 | ------------------- 18 | * avoid ROS segfault by returning early if ROS2 not ready 19 | * Contributors: Séverin Lemaignan 20 | 21 | 2.21.5 (2025-08-29) 22 | ------------------- 23 | * partially revert 857f033af7 to still use the underlying navigate_to_pose skill 24 | navigate_to_pose has been taught to deal with missing reference frames; for now we can use that. 25 | Keep the QML 'navigate' name in the API to be future-proof (when the proper 'navigate' skill will be ready) 26 | * Contributors: Séverin Lemaignan 27 | 28 | 2.21.4 (2025-08-28) 29 | ------------------- 30 | * skill: navigate_to_pose -> navigate 31 | * Contributors: Séverin Lemaignan 32 | 33 | 2.21.3 (2025-08-28) 34 | ------------------- 35 | * linting 36 | * allow Ros.point and Ros.pose without explicit frame 37 | * Contributors: Séverin Lemaignan 38 | 39 | 2.21.2 (2025-08-05) 40 | ------------------- 41 | * chat skill: configure the prompt in th default role 42 | * Contributors: Séverin Lemaignan 43 | 44 | 2.21.1 (2025-07-31) 45 | ------------------- 46 | * remove un-needed dependency on ament_cmake_pal 47 | * Contributors: Séverin Lemaignan 48 | 49 | 2.21.0 (2025-07-30) 50 | ------------------- 51 | * impl Chat skill 52 | * enable backward_ros to get stacktraces when plugin crashing 53 | * expose 'livespeech' topic to eg simulate someone speaking 54 | * Contributors: Séverin Lemaignan 55 | 56 | 2.20.1 (2025-07-29) 57 | ------------------- 58 | * service: setbool: ensure we notify when value changed 59 | * Contributors: Séverin Lemaignan 60 | 61 | 2.20.0 (2025-07-18) 62 | ------------------- 63 | * expose the navigate_to_pose skill 64 | * Contributors: Séverin Lemaignan 65 | 66 | 2.19.2 (2025-07-09) 67 | ------------------- 68 | * linting 69 | * Contributors: Séverin Lemaignan 70 | 71 | 2.19.1 (2025-07-08) 72 | ------------------- 73 | * ROS image provider: allows (and trims) '?...' after the topic name 74 | Useful to force QML to reload the image source 75 | * Contributors: Séverin Lemaignan 76 | 77 | 2.19.0 (2025-07-03) 78 | ------------------- 79 | * linting 80 | * improve logging 81 | * change how the Ros singleton is created, to make it possible to import it from JS modules in QML 82 | * improve API of look_at skill 83 | ROS PointStamped are created and passed with: Ros.point(frame,x,y,z) 84 | * disable float-equal warnings -- Qt MOC generates code that triggers that warning 85 | * implement the 'look_at' skill 86 | * Contributors: Séverin Lemaignan 87 | 88 | 2.18.1 (2025-07-02) 89 | ------------------- 90 | * linter 91 | * Contributors: Séverin Lemaignan 92 | 93 | 2.18.0 (2025-06-26) 94 | ------------------- 95 | * expose SetExpressionSkill 96 | * Contributors: Séverin Lemaignan 97 | 98 | 2.17.0 (2025-06-23) 99 | ------------------- 100 | * {/say -- /skill/say} 101 | * Contributors: Séverin Lemaignan 102 | 103 | 2.16.0 (2025-05-30) 104 | ------------------- 105 | * linting 106 | * Say skill: expose a 'say' method 107 | * Contributors: Séverin Lemaignan 108 | 109 | 2.15.1 (2025-05-30) 110 | ------------------- 111 | * add image_transport_plugins as an exec_depend 112 | otherwise, the QML engine will crash at runtime, as rosimage provider expects compressed video streams 113 | * Contributors: Séverin Lemaignan 114 | 115 | 2.15.0 (2025-05-28) 116 | ------------------- 117 | * add support for the Say skill 118 | * Contributors: Séverin Lemaignan 119 | 120 | 2.14.2 (2025-05-28) 121 | ------------------- 122 | * subscribe to images using BEST_EFFORT QoS 123 | * [doc] update the sample.qml file to use current API 124 | * Contributors: Séverin Lemaignan 125 | 126 | 2.14.1 (2025-05-20) 127 | ------------------- 128 | * when setting a topic value from within the QML, emit onValueCHanged 129 | * Contributors: Séverin Lemaignan 130 | 131 | 2.14.0 (2025-05-16) 132 | ------------------- 133 | * Create the publishers and subscribers only if the isPublisher or isSubscriber are true. Delete them once these variables are set false 134 | * Contributors: ferrangebelli 135 | 136 | 2.13.0 (2025-03-31) 137 | ------------------- 138 | * expose the properties isSubscriber/isPublisher to control the direction of Topics 139 | By default, topics are still bidirectional 140 | * Contributors: Séverin Lemaignan 141 | 142 | 2.12.0 (2025-03-31) 143 | ------------------- 144 | * intent topic: add support for 'source' field 145 | * Contributors: Séverin Lemaignan 146 | 147 | 2.11.0 (2025-03-26) 148 | ------------------- 149 | * added int32 subscriber 150 | * Contributors: ferrangebelli 151 | 152 | 2.10.0 (2025-01-16) 153 | ------------------- 154 | * add support to set custom ROS node name 155 | * add SetBoolService to create ROS SetBool service from QML 156 | * Contributors: Séverin Lemaignan 157 | 158 | 2.9.0 (2024-12-17) 159 | ------------------ 160 | * add SetUiFragment service 161 | * Contributors: Séverin Lemaignan 162 | 163 | 2.8.0 (2024-12-12) 164 | ------------------ 165 | * intent topic: add constants for all intent types 166 | * expose Intent.modality to the IntentTopic 167 | * Contributors: Séverin Lemaignan 168 | 169 | 2.7.0 (2024-10-29) 170 | ------------------ 171 | * setting remote parameter if it is set in qml on initialization 172 | * Add goal rejected signal for actions, and fix tests 173 | * Service and action not waiting for response, but triggering a callback 174 | * Get remote parameter on initialization 175 | * Uncrustify applied to pass tests 176 | * Added ros services and actions to the plugin 177 | * get language service first implementation 178 | * Contributors: Luka Juricic, ferrangebelli 179 | 180 | 2.6.1 (2024-10-15) 181 | ------------------ 182 | * linting 183 | * Contributors: Séverin Lemaignan 184 | 185 | 2.6.0 (2024-10-15) 186 | ------------------ 187 | * add support for string array parameters 188 | * Contributors: Séverin Lemaignan 189 | 190 | 2.5.0 (2024-10-15) 191 | ------------------ 192 | * add support for hri_actions_msgs::Intent topics 193 | * linting 194 | * Contributors: Séverin Lemaignan 195 | 196 | 2.4.1 (2024-10-15) 197 | ------------------ 198 | * [minor] linting 199 | * Contributors: Séverin Lemaignan 200 | 201 | 2.4.0 (2024-08-01) 202 | ------------------ 203 | * add support for ClosedCaptions 204 | While here, removed support for LiveSpeech 205 | * Contributors: Séverin Lemaignan 206 | 207 | 2.3.1 (2024-08-01) 208 | ------------------ 209 | * fix remote parameter setting/reading 210 | * Contributors: Séverin Lemaignan 211 | 212 | 2.3.0 (2024-08-01) 213 | ------------------ 214 | * add hooks to configure QML2_IMPORT_PATH 215 | * Contributors: Séverin Lemaignan 216 | 217 | 2.2.1 (2024-07-01) 218 | ------------------ 219 | * [linter] run ament_uncrustify 220 | * Contributors: Séverin Lemaignan 221 | 222 | 2.2.0 (2024-05-02) 223 | ------------------ 224 | * add subscriber/publisher for hri_msgs/Expression and hri_msgs/LiveSpeech 225 | * code layout refactoring 226 | moved the different QML objects in their own cpp/hpp 227 | * Contributors: Séverin Lemaignan 228 | 229 | 2.1.0 (2024-04-30) 230 | ------------------ 231 | * [doc] update README to reflect what the plugin can actually do 232 | * create a generic RosTopic class 233 | + expose IntTopic, FloatTopic, BoolTopic, String topic 234 | Remove (now useless) RosStringPublisher/Subscriber 235 | * add a RosTopicInt publisher/subscriber 236 | * add a RosParam qml object to set/get ROS2 parameters on the current node 237 | * minor Qt styling change 238 | * Contributors: Séverin Lemaignan 239 | 240 | 2.0.0 (2024-04-26) 241 | ------------------ 242 | * bump version in prep of first ROS2 release 243 | * add dep on ament_cmake_auto 244 | * handle more image formats 245 | * initial steps towards ROS2 port 246 | The whole source code now behaves as a regular ROS 2 package. It can be 247 | compile with colcon. 248 | Currently working QML objects: 249 | - RosStringPublisher 250 | - RosStringSubscriber 251 | - RosSignal 252 | - image subscribing via source: "image://rosimage/image_raw" 253 | * More documentation 254 | * More detailled documentation 255 | * Added missing dep. on visualization_msgs 256 | * [doc] list required deb packages to compile the plugin 257 | * Significantly improved documentation 258 | * [doc] Minor update 259 | * Fix many minor compilation warnings 260 | * ImagePublisher: Support latched image topic 261 | * Added support for reading and displaying ROS image topics 262 | This uses a QML ImageProvider. Specify the topic using: 263 | img.source = "image://rosimage/" 264 | Typical usage: 265 | Image { 266 | id: img 267 | cache: false 268 | anchors.fill: parent 269 | source: "image://rosimage/v4l/camera/image_raw" 270 | Timer { 271 | interval: 50 272 | repeat: true 273 | running: true 274 | onTriggered: { img.source = ""; img.source = "image://rosimage/v4l/camera/image_raw" } 275 | } 276 | } 277 | * add RosString publisher and subscriber 278 | * Added listener to signal 279 | * change RosPose to RosPoseListener and add RosPosePublisher with support for rotation 280 | * Make sure we do not send TF transforms with NaNs 281 | * Fixed a severe memory leak in ImagePublisher 282 | * added support for rotation in update of position 283 | * Update README.md 284 | Added cd build step 285 | And update known issues 286 | * Added a 'TFListener' to track a TF frame 287 | Similar to RosPose, but for TF frames 288 | * RosPose now exposes the 'z' value of the pose as well 289 | * [ImagePublisher] Publish as well camera info, using pixel2meter to provide a 'virtual' focal length 290 | * Added support to publish QML items as ROS images 291 | * Add support to set the ropic of RosPose 292 | While here, update doc 293 | * Added a property 'zoffset' to TfBroadcaster to the a custom Z value (0 by default) 294 | * Do not crash if a non-object it passed in Footprints targets 295 | * Added the 'RosSignal' type to publish an Empty on a topic whenever 'signal()' is called from QML 296 | * Added a property 'active' to TfBroadcaster to inhibit/activate broadcasting 297 | * Added a 'footprint' publisher, that publishes items' bounding boxes in a ROS MarkerArray 298 | * Listen by default on the topic 'poses' for poses 299 | * Ensure we always use scene coordinates 300 | * Set origin/pixel2meter conversion factors when receiving ROS pose 301 | * The ROS plugin can now listen to topics and send updates to the QT GUI thread 302 | * Added a README 303 | * Fixed scaling/rotation issues. User might now specify an item used as origin 304 | * TF transforms are now successfully published by the 'TFBroadcaster' QML item 305 | * First actual connection to ROS 306 | * Initial import of a QML plugin to export QML Item poses as ROS frames 307 | * Contributors: Emmanuel Senft, EmmanuelSenft, Séverin Lemaignan 308 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | 2 | Apache License 3 | Version 2.0, January 2004 4 | http://www.apache.org/licenses/ 5 | 6 | TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION 7 | 8 | 1. Definitions. 9 | 10 | "License" shall mean the terms and conditions for use, reproduction, 11 | and distribution as defined by Sections 1 through 9 of this document. 12 | 13 | "Licensor" shall mean the copyright owner or entity authorized by 14 | the copyright owner that is granting the License. 15 | 16 | "Legal Entity" shall mean the union of the acting entity and all 17 | other entities that control, are controlled by, or are under common 18 | control with that entity. For the purposes of this definition, 19 | "control" means (i) the power, direct or indirect, to cause the 20 | direction or management of such entity, whether by contract or 21 | otherwise, or (ii) ownership of fifty percent (50%) or more of the 22 | outstanding shares, or (iii) beneficial ownership of such entity. 23 | 24 | "You" (or "Your") shall mean an individual or Legal Entity 25 | exercising permissions granted by this License. 26 | 27 | "Source" form shall mean the preferred form for making modifications, 28 | including but not limited to software source code, documentation 29 | source, and configuration files. 30 | 31 | "Object" form shall mean any form resulting from mechanical 32 | transformation or translation of a Source form, including but 33 | not limited to compiled object code, generated documentation, 34 | and conversions to other media types. 35 | 36 | "Work" shall mean the work of authorship, whether in Source or 37 | Object form, made available under the License, as indicated by a 38 | copyright notice that is included in or attached to the work 39 | (an example is provided in the Appendix below). 40 | 41 | "Derivative Works" shall mean any work, whether in Source or Object 42 | form, that is based on (or derived from) the Work and for which the 43 | editorial revisions, annotations, elaborations, or other modifications 44 | represent, as a whole, an original work of authorship. For the purposes 45 | of this License, Derivative Works shall not include works that remain 46 | separable from, or merely link (or bind by name) to the interfaces of, 47 | the Work and Derivative Works thereof. 48 | 49 | "Contribution" shall mean any work of authorship, including 50 | the original version of the Work and any modifications or additions 51 | to that Work or Derivative Works thereof, that is intentionally 52 | submitted to Licensor for inclusion in the Work by the copyright owner 53 | or by an individual or Legal Entity authorized to submit on behalf of 54 | the copyright owner. For the purposes of this definition, "submitted" 55 | means any form of electronic, verbal, or written communication sent 56 | to the Licensor or its representatives, including but not limited to 57 | communication on electronic mailing lists, source code control systems, 58 | and issue tracking systems that are managed by, or on behalf of, the 59 | Licensor for the purpose of discussing and improving the Work, but 60 | excluding communication that is conspicuously marked or otherwise 61 | designated in writing by the copyright owner as "Not a Contribution." 62 | 63 | "Contributor" shall mean Licensor and any individual or Legal Entity 64 | on behalf of whom a Contribution has been received by Licensor and 65 | subsequently incorporated within the Work. 66 | 67 | 2. Grant of Copyright License. Subject to the terms and conditions of 68 | this License, each Contributor hereby grants to You a perpetual, 69 | worldwide, non-exclusive, no-charge, royalty-free, irrevocable 70 | copyright license to reproduce, prepare Derivative Works of, 71 | publicly display, publicly perform, sublicense, and distribute the 72 | Work and such Derivative Works in Source or Object form. 73 | 74 | 3. Grant of Patent License. Subject to the terms and conditions of 75 | this License, each Contributor hereby grants to You a perpetual, 76 | worldwide, non-exclusive, no-charge, royalty-free, irrevocable 77 | (except as stated in this section) patent license to make, have made, 78 | use, offer to sell, sell, import, and otherwise transfer the Work, 79 | where such license applies only to those patent claims licensable 80 | by such Contributor that are necessarily infringed by their 81 | Contribution(s) alone or by combination of their Contribution(s) 82 | with the Work to which such Contribution(s) was submitted. If You 83 | institute patent litigation against any entity (including a 84 | cross-claim or counterclaim in a lawsuit) alleging that the Work 85 | or a Contribution incorporated within the Work constitutes direct 86 | or contributory patent infringement, then any patent licenses 87 | granted to You under this License for that Work shall terminate 88 | as of the date such litigation is filed. 89 | 90 | 4. Redistribution. You may reproduce and distribute copies of the 91 | Work or Derivative Works thereof in any medium, with or without 92 | modifications, and in Source or Object form, provided that You 93 | meet the following conditions: 94 | 95 | (a) You must give any other recipients of the Work or 96 | Derivative Works a copy of this License; and 97 | 98 | (b) You must cause any modified files to carry prominent notices 99 | stating that You changed the files; and 100 | 101 | (c) You must retain, in the Source form of any Derivative Works 102 | that You distribute, all copyright, patent, trademark, and 103 | attribution notices from the Source form of the Work, 104 | excluding those notices that do not pertain to any part of 105 | the Derivative Works; and 106 | 107 | (d) If the Work includes a "NOTICE" text file as part of its 108 | distribution, then any Derivative Works that You distribute must 109 | include a readable copy of the attribution notices contained 110 | within such NOTICE file, excluding those notices that do not 111 | pertain to any part of the Derivative Works, in at least one 112 | of the following places: within a NOTICE text file distributed 113 | as part of the Derivative Works; within the Source form or 114 | documentation, if provided along with the Derivative Works; or, 115 | within a display generated by the Derivative Works, if and 116 | wherever such third-party notices normally appear. The contents 117 | of the NOTICE file are for informational purposes only and 118 | do not modify the License. You may add Your own attribution 119 | notices within Derivative Works that You distribute, alongside 120 | or as an addendum to the NOTICE text from the Work, provided 121 | that such additional attribution notices cannot be construed 122 | as modifying the License. 123 | 124 | You may add Your own copyright statement to Your modifications and 125 | may provide additional or different license terms and conditions 126 | for use, reproduction, or distribution of Your modifications, or 127 | for any such Derivative Works as a whole, provided Your use, 128 | reproduction, and distribution of the Work otherwise complies with 129 | the conditions stated in this License. 130 | 131 | 5. Submission of Contributions. Unless You explicitly state otherwise, 132 | any Contribution intentionally submitted for inclusion in the Work 133 | by You to the Licensor shall be under the terms and conditions of 134 | this License, without any additional terms or conditions. 135 | Notwithstanding the above, nothing herein shall supersede or modify 136 | the terms of any separate license agreement you may have executed 137 | with Licensor regarding such Contributions. 138 | 139 | 6. Trademarks. This License does not grant permission to use the trade 140 | names, trademarks, service marks, or product names of the Licensor, 141 | except as required for reasonable and customary use in describing the 142 | origin of the Work and reproducing the content of the NOTICE file. 143 | 144 | 7. Disclaimer of Warranty. Unless required by applicable law or 145 | agreed to in writing, Licensor provides the Work (and each 146 | Contributor provides its Contributions) on an "AS IS" BASIS, 147 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or 148 | implied, including, without limitation, any warranties or conditions 149 | of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A 150 | PARTICULAR PURPOSE. You are solely responsible for determining the 151 | appropriateness of using or redistributing the Work and assume any 152 | risks associated with Your exercise of permissions under this License. 153 | 154 | 8. Limitation of Liability. In no event and under no legal theory, 155 | whether in tort (including negligence), contract, or otherwise, 156 | unless required by applicable law (such as deliberate and grossly 157 | negligent acts) or agreed to in writing, shall any Contributor be 158 | liable to You for damages, including any direct, indirect, special, 159 | incidental, or consequential damages of any character arising as a 160 | result of this License or out of the use or inability to use the 161 | Work (including but not limited to damages for loss of goodwill, 162 | work stoppage, computer failure or malfunction, or any and all 163 | other commercial damages or losses), even if such Contributor 164 | has been advised of the possibility of such damages. 165 | 166 | 9. Accepting Warranty or Additional Liability. While redistributing 167 | the Work or Derivative Works thereof, You may choose to offer, 168 | and charge a fee for, acceptance of support, warranty, indemnity, 169 | or other liability obligations and/or rights consistent with this 170 | License. However, in accepting such obligations, You may act only 171 | on Your own behalf and on Your sole responsibility, not on behalf 172 | of any other Contributor, and only if You agree to indemnify, 173 | defend, and hold each Contributor harmless for any liability 174 | incurred by, or claims asserted against, such Contributor by reason 175 | of your accepting any such warranty or additional liability. 176 | 177 | END OF TERMS AND CONDITIONS 178 | 179 | APPENDIX: How to apply the Apache License to your work. 180 | 181 | To apply the Apache License to your work, attach the following 182 | boilerplate notice, with the fields enclosed by brackets "[]" 183 | replaced with your own identifying information. (Don't include 184 | the brackets!) The text should be enclosed in the appropriate 185 | comment syntax for the file format. We also recommend that a 186 | file or class name and description of purpose be included on the 187 | same "printed page" as the copyright notice for easier 188 | identification within third-party archives. 189 | 190 | Copyright [yyyy] [name of copyright owner] 191 | 192 | Licensed under the Apache License, Version 2.0 (the "License"); 193 | you may not use this file except in compliance with the License. 194 | You may obtain a copy of the License at 195 | 196 | http://www.apache.org/licenses/LICENSE-2.0 197 | 198 | Unless required by applicable law or agreed to in writing, software 199 | distributed under the License is distributed on an "AS IS" BASIS, 200 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 201 | See the License for the specific language governing permissions and 202 | limitations under the License. 203 | -------------------------------------------------------------------------------- /src/qml_rosparam.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2024 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #include "ros_qml_plugin/qml_rosparam.hpp" 16 | #include "ros_qml_plugin/ros2.hpp" 17 | 18 | using std::placeholders::_1; 19 | using namespace std::chrono_literals; 20 | 21 | RosParam::RosParam() {_node = Ros2Qml::getInstance().node();} 22 | 23 | void RosParam::setValue(QVariant value) 24 | { 25 | if (value != _value) { 26 | _value = value; 27 | } 28 | 29 | if (!_is_ready) { 30 | std::cerr << "Parameter service not ready yet" 31 | << std::endl; 32 | return; 33 | } 34 | 35 | bool remote_parameter = (_target_node_name != ""); 36 | 37 | if (remote_parameter) { 38 | if (!_param_client || !_param_client->service_is_ready()) { 39 | std::cerr << "Cannot set parameter " << _name.toStdString() << " on node " 40 | << _target_node_name.toStdString() 41 | << ": parameter service not ready" << std::endl; 42 | return; 43 | } 44 | } 45 | 46 | std::shared_ptr parameter; 47 | switch (value.type()) { 48 | case QVariant::Bool: 49 | parameter = std::make_shared( 50 | _name.toStdString(), 51 | value.toBool()); 52 | break; 53 | case QVariant::Int: 54 | parameter = 55 | std::make_shared(_name.toStdString(), value.toInt()); 56 | break; 57 | case QVariant::Double: 58 | parameter = std::make_shared( 59 | _name.toStdString(), 60 | value.toDouble()); 61 | break; 62 | case QVariant::String: 63 | parameter = std::make_shared( 64 | _name.toStdString(), value.toString().toStdString()); 65 | break; 66 | case QVariant::UserType: 67 | case QVariant::StringList: 68 | { 69 | if (value.canConvert() && value.convert(QVariant::StringList)) { 70 | auto stringList = value.toStringList(); 71 | std::vector v; 72 | v.reserve(stringList.size()); // Reserve memory for efficiency 73 | 74 | for (const QString & qStr : stringList) { 75 | v.push_back(qStr.toStdString()); // Convert each QString to std::string 76 | } 77 | 78 | parameter = std::make_shared( 79 | _name.toStdString(), v); 80 | 81 | } else { 82 | std::cerr << "Unsupported user type for parameter value: " << value.typeName() 83 | << std::endl; 84 | } 85 | } 86 | break; 87 | default: 88 | std::cerr << "Unsupported type for parameter value: " << value.typeName() 89 | << std::endl; 90 | } 91 | 92 | if (parameter) { 93 | if (remote_parameter) { 94 | _param_client->set_parameters({*parameter}); 95 | } else { 96 | _node->set_parameter(*parameter); 97 | } 98 | } 99 | } 100 | 101 | void RosParam::onRos2Initialized() 102 | { 103 | if (_name.isEmpty()) { 104 | std::cerr << "Cannot configure a parameter without a name" << std::endl; 105 | return; 106 | } 107 | 108 | bool remote_parameter = (_target_node_name != ""); 109 | 110 | if (remote_parameter) { 111 | /////////////////////////////////////////////////////////////////////////// 112 | // REMOTE PARAMETER 113 | 114 | if (!Ros2Qml::getInstance().isInitialized()) { 115 | std::cerr 116 | << "ROS 2 not yet initialized! Cannot configure a remote parameter." 117 | << std::endl; 118 | return; 119 | } 120 | 121 | if (!_param_client) { 122 | std::cout << "Creating new parameter client for node " 123 | << _target_node_name.toStdString() << std::endl; 124 | _param_client = std::make_shared( 125 | _node, _target_node_name.toStdString()); 126 | } 127 | 128 | if (!_param_client->service_is_ready()) { 129 | bool ok = _param_client->wait_for_service(1s); 130 | if (!ok) { 131 | std::cerr << "Could not connect to parameter service for node " 132 | << _target_node_name.toStdString() << std::endl; 133 | return; 134 | } 135 | } 136 | 137 | // add callback to update the value when the parameter changes 138 | _remote_cb = _param_client->on_parameter_event( 139 | std::bind(&RosParam::onRemoteParameterEvent, this, _1)); 140 | 141 | // If the value is set in qml, set the remote parameter, otherwise get the remote value 142 | if (_value.isValid()) { 143 | _is_ready = true; 144 | setValue(_value); 145 | } else { 146 | auto parameters_future = _param_client->get_parameters({_name.toStdString()}); 147 | std::future_status status = parameters_future.wait_for(10s); 148 | if (status != std::future_status::ready) { 149 | std::cerr << "Failed to get parameter " << _name.toStdString() << std::endl; 150 | return; 151 | } 152 | auto parameters = parameters_future.get(); 153 | if (parameters.empty()) { 154 | std::cerr << "Parameter " << _name.toStdString() << 155 | " not found, could not initialize to the remote value" << std::endl; 156 | return; 157 | } 158 | 159 | auto parameter = parameters.front(); 160 | 161 | QVariant value = _value; 162 | 163 | switch (parameter.get_type()) { 164 | case rcl_interfaces::msg::ParameterType::PARAMETER_BOOL: 165 | value = QVariant::fromValue(parameter.as_bool()); 166 | break; 167 | case rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER: 168 | value = QVariant::fromValue(parameter.as_int()); 169 | break; 170 | case rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE: 171 | value = QVariant::fromValue(parameter.as_double()); 172 | break; 173 | case rcl_interfaces::msg::ParameterType::PARAMETER_STRING: 174 | value = QVariant::fromValue(QString::fromStdString(parameter.as_string())); 175 | break; 176 | case rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY: 177 | { 178 | QStringList stringList; 179 | for (const auto & s : parameter.as_string_array()) { 180 | stringList.append(QString::fromStdString(s)); 181 | } 182 | value = QVariant::fromValue(stringList); 183 | } 184 | break; 185 | default: 186 | std::cerr << "Unsupported type " << parameter.get_type() << " for ROS2 parameter " << 187 | parameter.get_name() << " of node " << _target_node_name.toStdString() << std::endl; 188 | } 189 | if (value != _value) { 190 | _value = value; 191 | emit onValueChanged(); 192 | } 193 | _is_ready = true; 194 | } 195 | } else { 196 | /////////////////////////////////////////////////////////////////////////// 197 | // LOCAL PARAMETER 198 | 199 | if (!_value.isValid()) { 200 | std::cerr << "Cannot configure a parameter without a type; set 'value' to " 201 | "a default value" 202 | << std::endl; 203 | return; 204 | } 205 | 206 | _local_cb = _node->add_on_set_parameters_callback( 207 | std::bind(&RosParam::onLocalParameterEvent, this, _1)); 208 | 209 | QVariant updated_value = _value; 210 | 211 | if (_value.isValid()) { 212 | switch (_value.type()) { 213 | case QVariant::Bool: 214 | updated_value = QVariant::fromValue( 215 | _node->declare_parameter(_name.toStdString(), _value.toBool())); 216 | break; 217 | case QVariant::Int: 218 | updated_value = QVariant::fromValue( 219 | _node->declare_parameter(_name.toStdString(), _value.toInt())); 220 | break; 221 | case QVariant::Double: 222 | updated_value = QVariant::fromValue( 223 | _node->declare_parameter(_name.toStdString(), _value.toDouble())); 224 | break; 225 | case QVariant::String: 226 | updated_value = 227 | QVariant::fromValue( 228 | QString::fromStdString( 229 | _node->declare_parameter( 230 | _name.toStdString(), _value.toString().toStdString()))); 231 | break; 232 | default: 233 | std::cerr << "Unsupported type for parameter value" << std::endl; 234 | } 235 | } else { 236 | std::cerr << "Need to specify an initial value for parameter " 237 | << _name.toStdString() 238 | << ", as ROS2 requires us to known the parameter type" 239 | << std::endl; 240 | // value = _node->declare_parameter(_name.toStdString()); 241 | } 242 | 243 | // if the value was set at runtime, retrieve it and emit the signal 244 | if (updated_value.isValid() && updated_value != _value) { 245 | _value = updated_value; 246 | emit onValueChanged(); 247 | } 248 | _is_ready = true; 249 | } 250 | } 251 | 252 | rcl_interfaces::msg::SetParametersResult RosParam::onLocalParameterEvent( 253 | const std::vector & parameters) 254 | { 255 | rcl_interfaces::msg::SetParametersResult result; 256 | result.successful = true; 257 | 258 | QVariant value = _value; 259 | 260 | for (const auto & parameter : parameters) { 261 | if (parameter.get_name() == _name.toStdString()) { 262 | switch (parameter.get_type()) { 263 | case rclcpp::ParameterType::PARAMETER_BOOL: 264 | value = QVariant::fromValue(parameter.get_value()); 265 | break; 266 | case rclcpp::ParameterType::PARAMETER_INTEGER: 267 | value = QVariant::fromValue(parameter.get_value()); 268 | break; 269 | case rclcpp::ParameterType::PARAMETER_DOUBLE: 270 | value = QVariant::fromValue(parameter.get_value()); 271 | break; 272 | case rclcpp::ParameterType::PARAMETER_STRING: 273 | value = QVariant::fromValue( 274 | QString::fromStdString(parameter.get_value())); 275 | break; 276 | default: 277 | std::cerr << "Unsupported type " << parameter.get_type_name() 278 | << " for ROS2 parameter " << parameter.get_name() 279 | << std::endl; 280 | } 281 | 282 | if (value != _value) { 283 | _value = value; 284 | emit onValueChanged(); 285 | } 286 | } 287 | } 288 | 289 | return result; 290 | } 291 | 292 | void RosParam::onRemoteParameterEvent( 293 | const rcl_interfaces::msg::ParameterEvent::SharedPtr event) 294 | { 295 | QVariant value = _value; 296 | 297 | for (const auto & p : event->changed_parameters) { 298 | if (p.name == _name.toStdString()) { 299 | switch (p.value.type) { 300 | case rcl_interfaces::msg::ParameterType::PARAMETER_BOOL: 301 | value = QVariant::fromValue(p.value.bool_value); 302 | break; 303 | case rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER: 304 | value = QVariant::fromValue(p.value.integer_value); 305 | break; 306 | case rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE: 307 | value = QVariant::fromValue(p.value.double_value); 308 | break; 309 | case rcl_interfaces::msg::ParameterType::PARAMETER_STRING: 310 | value = 311 | QVariant::fromValue(QString::fromStdString(p.value.string_value)); 312 | break; 313 | case rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY: 314 | { 315 | QStringList stringList; 316 | for (const auto & s : p.value.string_array_value) { 317 | stringList.append(QString::fromStdString(s)); 318 | } 319 | value = QVariant::fromValue(stringList); 320 | } 321 | break; 322 | default: 323 | std::cerr << "Unsupported type " << p.value.type 324 | << " for ROS2 parameter " << p.name << " of node " 325 | << _target_node_name.toStdString() << std::endl; 326 | } 327 | if (value != _value) { 328 | _value = value; 329 | emit onValueChanged(); 330 | } 331 | 332 | break; 333 | } 334 | } 335 | } 336 | -------------------------------------------------------------------------------- /src/qml_rostopic.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2024 PAL Robotics S.L. All rights reserved. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | 23 | #include "ros_qml_plugin/qml_rostopic.hpp" 24 | #include "ros_qml_plugin/ros2.hpp" 25 | 26 | using std::placeholders::_1; 27 | 28 | // specialization for hri_msgs::msg::Expression 29 | template<> 30 | void RosTopicImpl::onIncomingData( 31 | const hri_msgs::msg::Expression & data) 32 | { 33 | if (!_is_subscriber) { 34 | return; 35 | } 36 | 37 | QVariant value = QVariant::fromValue(QString::fromStdString(data.expression)); 38 | 39 | if (value != _value) { 40 | _value = value; 41 | emit onValueChanged(); 42 | } 43 | 44 | // always emit the signal to signal a message has been published, even if the 45 | // value did not change 46 | emit messageReceived(); 47 | } 48 | 49 | // specialization for hri_actions_msgs::msg::ClosedCaption 50 | void ClosedCaptionTopic::onIncomingData( 51 | const hri_actions_msgs::msg::ClosedCaption & data) 52 | { 53 | if (!_is_subscriber) { 54 | return; 55 | } 56 | 57 | QVariant value = QVariant::fromValue(QString::fromStdString(data.text)); 58 | QString speaker_id = QString::fromStdString(data.speaker_id); 59 | 60 | if (value != _value || speaker_id != _speaker_id) { 61 | _value = value; 62 | _speaker_id = speaker_id; 63 | emit onValueChanged(); 64 | } 65 | 66 | // always emit the signal to signal a message has been received, even if the 67 | // value did not change 68 | emit messageReceived(); 69 | } 70 | 71 | // we need to instantiate the template for ClosedCaption, but we don't need to 72 | // implement the onIncomingData method here, as it is already implemented in the 73 | // ClosedCaptionTopic class 74 | template<> 75 | void RosTopicImpl::onIncomingData( 76 | const hri_actions_msgs::msg::ClosedCaption &) {} 77 | 78 | /////////////////////////////////////////////////////////// 79 | // specialization for hri_msgs::msg::LiveSpeech 80 | void LiveSpeechTopic::onIncomingData( 81 | const hri_msgs::msg::LiveSpeech & data) 82 | { 83 | if (!_is_subscriber) { 84 | return; 85 | } 86 | 87 | QVariant value = QVariant::fromValue(QString::fromStdString(data.final)); 88 | QString incremental = QString::fromStdString(data.incremental); 89 | double confidence = data.confidence; 90 | QString locale = QString::fromStdString(data.locale); 91 | 92 | setValue(value); // emits onValueChanged() if value changed 93 | 94 | if (incremental != _incremental) { 95 | _incremental = incremental; 96 | emit onIncrementalChanged(); 97 | } 98 | 99 | _confidence = confidence; 100 | _locale = locale; 101 | 102 | // always emit the signal to signal a message has been received, even if the 103 | // value did not change 104 | emit messageReceived(); 105 | } 106 | 107 | template<> 108 | void RosTopicImpl::onIncomingData( 109 | const hri_msgs::msg::LiveSpeech &) {} 110 | 111 | void LiveSpeechTopic::publish() 112 | { 113 | if (!_is_publisher) { 114 | std::cerr << "Calling publish() on a topic marked as non-publisher." << std::endl; 115 | return; 116 | } 117 | 118 | if (_speaker_name.isEmpty()) { 119 | setSpeakerName("anonymous_speaker"); 120 | } 121 | 122 | if (!_publisher) { 123 | std::cerr << "LiveSpeechTopic.publish() called without a publisher." << std::endl; 124 | return; 125 | } 126 | 127 | if (std::string(_publisher->get_topic_name()).empty()) { 128 | std::cerr << "LiveSpeechTopic.publish() called without any topic." << std::endl; 129 | return; 130 | } 131 | 132 | if (!_user_id_publisher) { 133 | // Destroy the old publisher, if it exists. This means that the 134 | // topic has been changed, and we need to create a new publisher. 135 | std::shared_ptr node = Ros2Qml::getInstance().node(); 136 | _user_id_publisher = node->create_publisher( 137 | "/humans/voices/tracked", 138 | 1); 139 | } 140 | 141 | hri_msgs::msg::IdsList user_ids; 142 | user_ids.ids.push_back(_speaker_name.toStdString()); 143 | _user_id_publisher->publish(user_ids); 144 | 145 | hri_msgs::msg::LiveSpeech message; 146 | message.final = _value.value().toStdString(); 147 | message.incremental = _incremental.toStdString(); 148 | message.confidence = _confidence; 149 | message.locale = _locale.toStdString(); 150 | 151 | _publisher->publish(message); 152 | } 153 | 154 | template<> 155 | void RosTopicImpl::publish() {} 156 | 157 | void LiveSpeechTopic::setSpeakerName(const QString & speaker_name) 158 | { 159 | if (speaker_name == _speaker_name) { 160 | return; 161 | } 162 | 163 | _speaker_name = speaker_name; 164 | 165 | setTopic("/humans/voices/" + _speaker_name + "/speech"); 166 | } 167 | 168 | /////////////////////////////////////////////////////////////// 169 | // specialization for hri_actions_msgs::msg::Intent 170 | void IntentTopic::onIncomingData( 171 | const hri_actions_msgs::msg::Intent & msg) 172 | { 173 | if (!_is_subscriber) { 174 | return; 175 | } 176 | 177 | QVariant value = QVariant::fromValue(QString::fromStdString(msg.intent)); 178 | QString data = QString::fromStdString(msg.data); 179 | QString modality = QString::fromStdString(msg.modality); 180 | QString source = QString::fromStdString(msg.source); 181 | 182 | if (value != _value || 183 | data != _data || 184 | modality != _modality || 185 | source != _source) 186 | { 187 | _value = value; 188 | _data = data; 189 | _modality = modality; 190 | _source = source; 191 | emit onValueChanged(); 192 | } 193 | 194 | // always emit the signal to signal a message has been received, even if the 195 | // value did not change 196 | emit messageReceived(); 197 | } 198 | 199 | template<> 200 | void RosTopicImpl::onIncomingData( 201 | const hri_actions_msgs::msg::Intent &) {} 202 | 203 | void IntentTopic::publish() 204 | { 205 | if (!_is_publisher) { 206 | std::cerr << "Calling publish() on a topic marked as non-publisher." << std::endl; 207 | return; 208 | } 209 | 210 | if (!_publisher) { 211 | std::cerr << "IntentTopic.publish() called without a publisher." << std::endl; 212 | return; 213 | } 214 | 215 | if (std::string(_publisher->get_topic_name()).empty()) { 216 | std::cerr << "IntentTopic.publish() called without any topic." << std::endl; 217 | return; 218 | } 219 | 220 | hri_actions_msgs::msg::Intent message; 221 | message.intent = _value.value().toStdString(); 222 | message.data = _data.toStdString(); 223 | message.modality = _modality.toStdString(); 224 | message.source = _source.toStdString(); 225 | 226 | _publisher->publish(message); 227 | } 228 | 229 | template<> 230 | void RosTopicImpl::publish() {} 231 | 232 | /////////////////////////////////////////////////////////////////////////////// 233 | template void RosTopicImpl::onIncomingData(const T & data) 234 | { 235 | if (!_is_subscriber) { 236 | return; 237 | } 238 | 239 | QVariant value; 240 | 241 | // special case std::string, as they are not directly convertible to QVariant 242 | if constexpr (std::is_same_v) { 243 | value = QVariant::fromValue(QString::fromStdString(data.data)); 244 | } else { 245 | value = QVariant::fromValue(data.data); 246 | } 247 | 248 | if (value != _value) { 249 | _value = value; 250 | emit onValueChanged(); 251 | } 252 | 253 | // always emit the signal to signal a message has been published, even if the 254 | // value did not change 255 | emit messageReceived(); 256 | } 257 | 258 | template void RosTopicImpl::setTopic(const QString & topic) 259 | { 260 | if (topic == _topic) { 261 | return; 262 | } 263 | 264 | std::shared_ptr node = Ros2Qml::getInstance().node(); 265 | 266 | if (_is_subscriber) { // Create the subscriber only if the topic is set to subscribe 267 | if (_subscriber) { 268 | // Destroy the old subscriber, if it exists. This means that the 269 | // topic has been changed, and we need to create a new subscriber. 270 | _subscriber.reset(); 271 | } 272 | _subscriber = node->create_subscription( 273 | topic.toStdString(), 1, 274 | std::bind(&RosTopicImpl::onIncomingData, this, _1)); 275 | } 276 | 277 | if (_is_publisher) { // Create the publisher only if the topic is set to publish 278 | if (_publisher) { 279 | // Destroy the old publisher, if it exists. This means that the 280 | // topic has been changed, and we need to create a new publisher. 281 | _publisher.reset(); 282 | } 283 | _publisher = node->create_publisher(topic.toStdString(), 1); 284 | } 285 | 286 | _topic = topic; 287 | } 288 | 289 | template void RosTopicImpl::setValue(const QVariant & value) 290 | { 291 | if (value == _value) { 292 | return; 293 | } 294 | 295 | _value = value; 296 | emit onValueChanged(); 297 | 298 | if (_is_publisher) { 299 | publish(); 300 | } 301 | } 302 | 303 | template void RosTopicImpl::setIsPublisher(const bool & is_publisher) 304 | { 305 | if (is_publisher == _is_publisher) { 306 | return; 307 | } 308 | 309 | _is_publisher = is_publisher; 310 | 311 | if (!_is_publisher) { 312 | if (_publisher) { 313 | // Destroy the old publisher, if it exists. 314 | _publisher.reset(); 315 | } 316 | } else { 317 | // Create the publisher 318 | if (!_topic.isEmpty()) { 319 | std::shared_ptr node = Ros2Qml::getInstance().node(); 320 | _publisher = node->create_publisher(_topic.toStdString(), 1); 321 | } 322 | } 323 | } 324 | 325 | template void RosTopicImpl::setIsSubscriber(const bool & is_subscriber) 326 | { 327 | if (is_subscriber == _is_subscriber) { 328 | return; 329 | } 330 | 331 | _is_subscriber = is_subscriber; 332 | 333 | if (!_is_subscriber) { 334 | if (_subscriber) { 335 | // Destroy the old subscriber, if it exists. 336 | _subscriber.reset(); 337 | } 338 | } else { 339 | // Create the subscriber 340 | if (!_topic.isEmpty()) { 341 | std::shared_ptr node = Ros2Qml::getInstance().node(); 342 | _subscriber = node->create_subscription( 343 | _topic.toStdString(), 1, 344 | std::bind(&RosTopicImpl::onIncomingData, this, _1)); 345 | } 346 | } 347 | } 348 | 349 | template<> void RosTopicImpl::publish() 350 | { 351 | if (!_is_publisher) { 352 | std::cerr << "Calling publish() on a topic marked as non-publisher." << std::endl; 353 | return; 354 | } 355 | 356 | if (!_publisher) { 357 | std::cerr << "RosTopic.publish() called without a publisher." << std::endl; 358 | return; 359 | } 360 | 361 | if (std::string(_publisher->get_topic_name()).empty()) { 362 | std::cerr << "RosTopic.publish() called without any topic." << std::endl; 363 | return; 364 | } 365 | 366 | hri_msgs::msg::Expression message; 367 | message.expression = _value.value().toStdString(); 368 | 369 | _publisher->publish(message); 370 | } 371 | 372 | template<> void RosTopicImpl::publish() 373 | { 374 | std::cerr << "Publishing a ClosedCaption msg from QML is not supported." 375 | << std::endl; 376 | return; 377 | } 378 | 379 | 380 | template void RosTopicImpl::publish() 381 | { 382 | if (!_is_publisher) { 383 | std::cerr << "Calling publish() on a topic marked as non-publisher." << std::endl; 384 | return; 385 | } 386 | 387 | if (!_publisher) { 388 | std::cerr << "RosTopic.publish() called without a publisher." << std::endl; 389 | return; 390 | } 391 | 392 | if (std::string(_publisher->get_topic_name()).empty()) { 393 | std::cerr << "RosTopic.publish() called without any topic." << std::endl; 394 | return; 395 | } 396 | 397 | T message; 398 | 399 | // special case std::string, as they are not directly convertible from 400 | // QVariant 401 | if constexpr (std::is_same_v) { 402 | message.data = _value.value().toStdString(); 403 | } else { 404 | message.data = _value.value(); 405 | } 406 | 407 | _publisher->publish(message); 408 | } 409 | 410 | template class RosTopicImpl; 411 | template class RosTopicImpl; 412 | template class RosTopicImpl; 413 | template class RosTopicImpl; 414 | template class RosTopicImpl; 415 | template class RosTopicImpl; 416 | template class RosTopicImpl; 417 | template class RosTopicImpl; 418 | template class RosTopicImpl; 419 | --------------------------------------------------------------------------------