From 7d4ab560c4c0041bae51ef89b817175e31ad2778 Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Wed, 21 Oct 2020 23:13:59 -0700 Subject: [PATCH 01/21] init plugin template Signed-off-by: John Shepherd --- src/gui/plugins/CMakeLists.txt | 1 + src/gui/plugins/tape_measure/CMakeLists.txt | 8 ++ src/gui/plugins/tape_measure/TapeMeasure.cc | 103 ++++++++++++++++++ src/gui/plugins/tape_measure/TapeMeasure.hh | 65 +++++++++++ src/gui/plugins/tape_measure/TapeMeasure.qml | 70 ++++++++++++ src/gui/plugins/tape_measure/TapeMeasure.qrc | 6 + src/gui/plugins/tape_measure/tape_measure.svg | 82 ++++++++++++++ 7 files changed, 335 insertions(+) create mode 100644 src/gui/plugins/tape_measure/CMakeLists.txt create mode 100644 src/gui/plugins/tape_measure/TapeMeasure.cc create mode 100644 src/gui/plugins/tape_measure/TapeMeasure.hh create mode 100644 src/gui/plugins/tape_measure/TapeMeasure.qml create mode 100644 src/gui/plugins/tape_measure/TapeMeasure.qrc create mode 100644 src/gui/plugins/tape_measure/tape_measure.svg diff --git a/src/gui/plugins/CMakeLists.txt b/src/gui/plugins/CMakeLists.txt index 7cca6905e6..35a4d49fa4 100644 --- a/src/gui/plugins/CMakeLists.txt +++ b/src/gui/plugins/CMakeLists.txt @@ -89,6 +89,7 @@ add_subdirectory(playback_scrubber) add_subdirectory(resource_spawner) add_subdirectory(scene3d) add_subdirectory(shapes) +add_subdirectory(tape_measure) add_subdirectory(transform_control) add_subdirectory(video_recorder) add_subdirectory(view_angle) diff --git a/src/gui/plugins/tape_measure/CMakeLists.txt b/src/gui/plugins/tape_measure/CMakeLists.txt new file mode 100644 index 0000000000..4b8869c9a8 --- /dev/null +++ b/src/gui/plugins/tape_measure/CMakeLists.txt @@ -0,0 +1,8 @@ +gz_add_gui_plugin(TapeMeasure + SOURCES TapeMeasure.cc + QT_HEADERS TapeMeasure.hh + PRIVATE_LINK_LIBS + ${IGNITION-RENDERING_LIBRARIES} +) + + diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc new file mode 100644 index 0000000000..6d23909866 --- /dev/null +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -0,0 +1,103 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "ignition/gazebo/components/Name.hh" +#include "ignition/gazebo/components/ParentEntity.hh" +#include "ignition/gazebo/EntityComponentManager.hh" +#include "ignition/gazebo/gui/GuiEvents.hh" + +#include "TapeMeasure.hh" + +namespace ignition::gazebo +{ + class TapeMeasurePrivate + { + /// \brief Ignition communication node. + public: transport::Node node; + + /// \brief Mutex to protect mode + public: std::mutex mutex; + + public: bool measure = false; + }; +} + +using namespace ignition; +using namespace gazebo; + +///////////////////////////////////////////////// +TapeMeasure::TapeMeasure() + : ignition::gui::Plugin(), + dataPtr(std::make_unique()) +{ +} + +///////////////////////////////////////////////// +TapeMeasure::~TapeMeasure() = default; + +///////////////////////////////////////////////// +void TapeMeasure::LoadConfig(const tinyxml2::XMLElement *) +{ + if (this->title.empty()) + this->title = "Tape measure"; + + ignition::gui::App()->findChild + ()->installEventFilter(this); +} + +///////////////////////////////////////////////// +void TapeMeasure::OnMeasure() +{ + this->dataPtr->measure = true; +} + +///////////////////////////////////////////////// +bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) +{ + if (_event->type() == ignition::gazebo::gui::events::Render::kType) + { + // This event is called in Scene3d's RenderThread, so it's safe to make + // rendering calls here + // TODO do any rendering here + if (this->dataPtr->measure) + { + ignwarn << "Measuring" << std::endl; + this->dataPtr->measure = false; + } + } + return QObject::eventFilter(_obj, _event); +} +// Register this plugin +IGNITION_ADD_PLUGIN(ignition::gazebo::TapeMeasure, + ignition::gui::Plugin) diff --git a/src/gui/plugins/tape_measure/TapeMeasure.hh b/src/gui/plugins/tape_measure/TapeMeasure.hh new file mode 100644 index 0000000000..b07ac97880 --- /dev/null +++ b/src/gui/plugins/tape_measure/TapeMeasure.hh @@ -0,0 +1,65 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#ifndef IGNITION_GAZEBO_GUI_TAPEMEASURE_HH_ +#define IGNITION_GAZEBO_GUI_TAPEMEASURE_HH_ + +#include + +#include + +namespace ignition +{ +namespace gazebo +{ + class TapeMeasurePrivate; + + /// \brief Provides buttons for translation, rotation, and scale + /// + /// ## Configuration + /// \ : Set the service to receive transform mode requests. + class TapeMeasure : public ignition::gui::Plugin + { + Q_OBJECT + + /// \brief Constructor + public: TapeMeasure(); + + /// \brief Destructor + public: ~TapeMeasure() override; + + // Documentation inherited + public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override; + + /// \brief Callback to retrieve existing grid. Should only be called + /// within the render thread. If no grid is found, the grid pointer + /// is not updated. + public: void LoadGrid(); + + // Documentation inherited + protected: bool eventFilter(QObject *_obj, QEvent *_event) override; + + public slots: void OnMeasure(); + + /// \internal + /// \brief Pointer to private data. + private: std::unique_ptr dataPtr; + }; +} +} + +#endif diff --git a/src/gui/plugins/tape_measure/TapeMeasure.qml b/src/gui/plugins/tape_measure/TapeMeasure.qml new file mode 100644 index 0000000000..98fac16636 --- /dev/null +++ b/src/gui/plugins/tape_measure/TapeMeasure.qml @@ -0,0 +1,70 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +import QtQuick 2.9 +import QtQuick.Window 2.2 +import QtQuick.Controls 2.1 +import QtQuick.Controls.Material 2.2 +import QtQuick.Controls.Material.impl 2.2 +import QtQuick.Layouts 1.3 +import QtQuick.Controls.Styles 1.4 +import "qrc:/qml" + +ToolBar { + id: tapeMeasure + Layout.minimumWidth: 200 + Layout.minimumHeight: 100 + + property color snapTitle: (Material.theme == Material.Light) ? + Material.color(Material.Grey, Material.Shade900) : + Material.color(Material.Grey, Material.Shade200) + + property color snapItem: (Material.theme == Material.Light) ? + Material.color(Material.Grey, Material.Shade800) : + Material.color(Material.Grey, Material.Shade100) + + background: Rectangle { + color: "transparent" + } + + ButtonGroup { + id: group + } + + RowLayout { + spacing: 2 + ToolButton { + id: select + checkable: true + checked: true + ButtonGroup.group: group + ToolTip.text: "Tape Measure Tool" + ToolTip.visible: hovered + ToolTip.delay: Qt.styleHints.mousePressAndHoldInterval + contentItem: Image { + fillMode: Image.Pad + horizontalAlignment: Image.AlignHCenter + verticalAlignment: Image.AlignVCenter + source: "tape_measure.svg" + sourceSize.width: 24; + sourceSize.height: 24; + } + onClicked: { + TapeMeasure.OnMeasure(); + } + } + } +} diff --git a/src/gui/plugins/tape_measure/TapeMeasure.qrc b/src/gui/plugins/tape_measure/TapeMeasure.qrc new file mode 100644 index 0000000000..b4f504c64f --- /dev/null +++ b/src/gui/plugins/tape_measure/TapeMeasure.qrc @@ -0,0 +1,6 @@ + + + TapeMeasure.qml + tape_measure.svg + + diff --git a/src/gui/plugins/tape_measure/tape_measure.svg b/src/gui/plugins/tape_measure/tape_measure.svg new file mode 100644 index 0000000000..20b65f8e7c --- /dev/null +++ b/src/gui/plugins/tape_measure/tape_measure.svg @@ -0,0 +1,82 @@ + + + +image/svg+xml + + + + + + \ No newline at end of file From 32236cca3749cc48735b1c12464167dde0b859ae Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Wed, 28 Oct 2020 12:44:47 -0700 Subject: [PATCH 02/21] some updates Signed-off-by: John Shepherd --- src/gui/plugins/scene3d/Scene3D.cc | 1 + src/gui/plugins/tape_measure/TapeMeasure.cc | 37 +++++++++++---------- src/gui/plugins/tape_measure/TapeMeasure.hh | 8 ----- 3 files changed, 21 insertions(+), 25 deletions(-) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 053fcd003a..0ba32a3666 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -1413,6 +1413,7 @@ void IgnRenderer::HandleMouseViewControl() { this->dataPtr->target = this->ScreenToScene( this->dataPtr->mouseEvent.PressPos()); + ignwarn << "target click is x: " << this->dataPtr->target[0] << ", y: " << this->dataPtr->target[1] << ", z: " << this->dataPtr->target[2] << std::endl; this->dataPtr->viewControl.SetTarget(this->dataPtr->target); } diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index 6d23909866..cdd8ebb887 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -79,25 +79,28 @@ void TapeMeasure::LoadConfig(const tinyxml2::XMLElement *) ///////////////////////////////////////////////// void TapeMeasure::OnMeasure() { - this->dataPtr->measure = true; -} + std::string modelSdfString = std::string("" + "" + "" + "0 0 0 0 0 0" + "" + "" + "" + "" + "0.1" + "" + "" + "" + "" + "" + ""); -///////////////////////////////////////////////// -bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) -{ - if (_event->type() == ignition::gazebo::gui::events::Render::kType) - { - // This event is called in Scene3d's RenderThread, so it's safe to make - // rendering calls here - // TODO do any rendering here - if (this->dataPtr->measure) - { - ignwarn << "Measuring" << std::endl; - this->dataPtr->measure = false; - } - } - return QObject::eventFilter(_obj, _event); + gui::events::SpawnPreviewModel event(modelSdfString); + ignition::gui::App()->sendEvent( + ignition::gui::App()->findChild(), + &event); } + // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::TapeMeasure, ignition::gui::Plugin) diff --git a/src/gui/plugins/tape_measure/TapeMeasure.hh b/src/gui/plugins/tape_measure/TapeMeasure.hh index b07ac97880..f80f49b6ac 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.hh +++ b/src/gui/plugins/tape_measure/TapeMeasure.hh @@ -45,14 +45,6 @@ namespace gazebo // Documentation inherited public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override; - /// \brief Callback to retrieve existing grid. Should only be called - /// within the render thread. If no grid is found, the grid pointer - /// is not updated. - public: void LoadGrid(); - - // Documentation inherited - protected: bool eventFilter(QObject *_obj, QEvent *_event) override; - public slots: void OnMeasure(); /// \internal From a062e20a07795c49dfefdcd134b11217e6d38f22 Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Mon, 9 Nov 2020 23:33:22 -0800 Subject: [PATCH 03/21] Add marker placement Signed-off-by: John Shepherd --- include/ignition/gazebo/gui/GuiEvents.hh | 50 ++++++++++ src/gui/plugins/scene3d/Scene3D.cc | 43 +++++++- src/gui/plugins/scene3d/Scene3D.hh | 6 ++ src/gui/plugins/tape_measure/TapeMeasure.cc | 104 ++++++++++++++++---- src/gui/plugins/tape_measure/TapeMeasure.hh | 3 + 5 files changed, 182 insertions(+), 24 deletions(-) diff --git a/include/ignition/gazebo/gui/GuiEvents.hh b/include/ignition/gazebo/gui/GuiEvents.hh index 6af9c5a69c..e8a87e2ba4 100644 --- a/include/ignition/gazebo/gui/GuiEvents.hh +++ b/include/ignition/gazebo/gui/GuiEvents.hh @@ -210,6 +210,56 @@ namespace events /// \brief The path of SDF file to be previewed. std::string filePath; }; + + /// \brief Event called which broadcasts the 3D coordinates of a user's + /// mouse hover within the scene. + class HoverToScene : public QEvent + { + /// \brief Constructor + /// \param[in] _filePath The path to an SDF file. + public: explicit HoverToScene(const math::Vector3d &_point) + : QEvent(kType), point(_point) + { + } + + /// \brief Unique type for this event. + static const QEvent::Type kType = QEvent::Type(QEvent::User + 6); + + /// \brief Get the point within the scene that the user clicked. + /// \return The 3D point. + public: math::Vector3d Point() const + { + return this->point; + } + + /// \brief The 3D point that the user clicked. + private: math::Vector3d point; + }; + + /// \brief Event called which broadcasts the 3D coordinates of a user's + /// left click within the scene. + class LeftClickToScene : public QEvent + { + /// \brief Constructor + /// \param[in] _filePath The path to an SDF file. + public: explicit LeftClickToScene(const math::Vector3d &_point) + : QEvent(kType), point(_point) + { + } + + /// \brief Unique type for this event. + static const QEvent::Type kType = QEvent::Type(QEvent::User + 7); + + /// \brief Get the point within the scene that the user clicked. + /// \return The 3D point. + public: math::Vector3d Point() const + { + return this->point; + } + + /// \brief The 3D point that the user clicked. + private: math::Vector3d point; + }; } // namespace events } } // namespace gui diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 0ba32a3666..6459cf7d05 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -760,12 +760,42 @@ Entity IgnRenderer::UniqueId() void IgnRenderer::HandleMouseEvent() { std::lock_guard lock(this->dataPtr->mutex); + this->BroadcastHoverPos(); + this->BroadcastLeftClick(); this->HandleMouseContextMenu(); this->HandleModelPlacement(); this->HandleMouseTransformControl(); this->HandleMouseViewControl(); } +void IgnRenderer::BroadcastHoverPos() +{ + if (this->dataPtr->hoverDirty) + { + math::Vector3d pos = this->ScreenToScene(this->dataPtr->mouseHoverPos); + + gui::events::HoverToScene hoverToSceneEvent(pos); + ignition::gui::App()->sendEvent( + ignition::gui::App()->findChild(), + &hoverToSceneEvent); + } +} + +void IgnRenderer::BroadcastLeftClick() +{ + if (this->dataPtr->mouseEvent.Button() == common::MouseEvent::LEFT && + this->dataPtr->mouseEvent.Type() == common::MouseEvent::RELEASE && + !this->dataPtr->mouseEvent.Dragging() && this->dataPtr->mouseDirty) + { + math::Vector3d pos = this->ScreenToScene(this->dataPtr->mouseEvent.Pos()); + + gui::events::LeftClickToScene leftClickToSceneEvent(pos); + ignition::gui::App()->sendEvent( + ignition::gui::App()->findChild(), + &leftClickToSceneEvent); + } +} + ///////////////////////////////////////////////// void IgnRenderer::HandleMouseContextMenu() { @@ -1413,7 +1443,6 @@ void IgnRenderer::HandleMouseViewControl() { this->dataPtr->target = this->ScreenToScene( this->dataPtr->mouseEvent.PressPos()); - ignwarn << "target click is x: " << this->dataPtr->target[0] << ", y: " << this->dataPtr->target[1] << ", z: " << this->dataPtr->target[2] << std::endl; this->dataPtr->viewControl.SetTarget(this->dataPtr->target); } @@ -1821,12 +1850,18 @@ math::Vector3d IgnRenderer::ScreenToScene( this->dataPtr->camera, math::Vector2d(nx, ny)); auto result = this->dataPtr->rayQuery->ClosestPoint(); + math::Vector3d point; + if (result) - return result.point; + point = result.point; + else + { + point = this->dataPtr->rayQuery->Origin() + + this->dataPtr->rayQuery->Direction() * 10; + } // Set point to be 10m away if no intersection found - return this->dataPtr->rayQuery->Origin() + - this->dataPtr->rayQuery->Direction() * 10; + return point; } //////////////////////////////////////////////// diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index 5adf01854e..c8d1e192e9 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -351,6 +351,12 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Handle model placement requests private: void HandleModelPlacement(); + /// \brief Broadcasts the currently hovered 3d scene location. + private: void BroadcastHoverPos(); + + /// \brief Broadcasts a left click within the scene + private: void BroadcastLeftClick(); + /// \brief Generate a unique entity id. /// \return The unique entity id private: Entity UniqueId(); diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index cdd8ebb887..ec5169474a 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -16,6 +16,7 @@ */ #include #include +#include #include #include @@ -79,26 +80,89 @@ void TapeMeasure::LoadConfig(const tinyxml2::XMLElement *) ///////////////////////////////////////////////// void TapeMeasure::OnMeasure() { - std::string modelSdfString = std::string("" - "" - "" - "0 0 0 0 0 0" - "" - "" - "" - "" - "0.1" - "" - "" - "" - "" - "" - ""); - - gui::events::SpawnPreviewModel event(modelSdfString); - ignition::gui::App()->sendEvent( - ignition::gui::App()->findChild(), - &event); + this->dataPtr->measure = true; +} + +bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) +{ + if (_event->type() == ignition::gazebo::gui::events::HoverToScene::kType) + { + auto hoverToSceneEvent = + reinterpret_cast(_event); + + // This event is called in Scene3d's RenderThread, so it's safe to make + // rendering calls here + if (this->dataPtr->measure && hoverToSceneEvent) + { + // Delete the previously created marker + ignition::msgs::Marker markerMsg; + markerMsg.set_ns("default"); + markerMsg.set_id(1); + markerMsg.set_action(ignition::msgs::Marker::DELETE_MARKER); + this->dataPtr->node.Request("/marker", markerMsg); + + math::Vector3d point = hoverToSceneEvent->Point(); + markerMsg.set_ns("default"); + markerMsg.set_id(1); + markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); + markerMsg.set_type(ignition::msgs::Marker::SPHERE); + ignition::msgs::Set(markerMsg.mutable_scale(), + ignition::math::Vector3d(0.1, 0.1, 0.1)); + markerMsg.mutable_material()->mutable_ambient()->set_r(0.2); + markerMsg.mutable_material()->mutable_ambient()->set_g(0.2); + markerMsg.mutable_material()->mutable_ambient()->set_b(1); + markerMsg.mutable_material()->mutable_ambient()->set_a(1); + markerMsg.mutable_material()->mutable_diffuse()->set_r(0.2); + markerMsg.mutable_material()->mutable_diffuse()->set_g(0.2); + markerMsg.mutable_material()->mutable_diffuse()->set_b(1); + markerMsg.mutable_material()->mutable_diffuse()->set_a(1); + ignition::msgs::Set(markerMsg.mutable_pose(), + ignition::math::Pose3d(point.X(), point.Y(), point.Z(), 0, 0, 0)); + this->dataPtr->node.Request("/marker", markerMsg); + } + } + // Note: the following isn't an else if statement due to the hover scene + // event sometimes smothering this click event if the logic uses an else if + // statement + if (_event->type() == ignition::gazebo::gui::events::LeftClickToScene::kType) + { + auto leftClickToSceneEvent = + reinterpret_cast(_event); + + // This event is called in Scene3d's RenderThread, so it's safe to make + // rendering calls here + if (this->dataPtr->measure && leftClickToSceneEvent) + { + math::Vector3d point = leftClickToSceneEvent->Point(); + // Delete the previously created marker + ignition::msgs::Marker markerMsg; + markerMsg.set_ns("default"); + markerMsg.set_id(1); + markerMsg.set_action(ignition::msgs::Marker::DELETE_MARKER); + this->dataPtr->node.Request("/marker", markerMsg); + + markerMsg.set_ns("default"); + markerMsg.set_id(1); + markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); + markerMsg.set_type(ignition::msgs::Marker::SPHERE); + ignition::msgs::Set(markerMsg.mutable_scale(), + ignition::math::Vector3d(0.1, 0.1, 0.1)); + markerMsg.mutable_material()->mutable_ambient()->set_r(0); + markerMsg.mutable_material()->mutable_ambient()->set_g(0); + markerMsg.mutable_material()->mutable_ambient()->set_b(1); + markerMsg.mutable_material()->mutable_ambient()->set_a(1); + markerMsg.mutable_material()->mutable_diffuse()->set_r(0); + markerMsg.mutable_material()->mutable_diffuse()->set_g(0); + markerMsg.mutable_material()->mutable_diffuse()->set_b(1); + markerMsg.mutable_material()->mutable_diffuse()->set_a(1); + ignition::msgs::Set(markerMsg.mutable_pose(), + ignition::math::Pose3d(point.X(), point.Y(), point.Z(), 0, 0, 0)); + this->dataPtr->node.Request("/marker", markerMsg); + this->dataPtr->measure = false; + } + } + + return QObject::eventFilter(_obj, _event); } // Register this plugin diff --git a/src/gui/plugins/tape_measure/TapeMeasure.hh b/src/gui/plugins/tape_measure/TapeMeasure.hh index f80f49b6ac..8abb154d06 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.hh +++ b/src/gui/plugins/tape_measure/TapeMeasure.hh @@ -47,6 +47,9 @@ namespace gazebo public slots: void OnMeasure(); + // Documentation inherited + protected: bool eventFilter(QObject *_obj, QEvent *_event) override; + /// \internal /// \brief Pointer to private data. private: std::unique_ptr dataPtr; From af399c92a5c681e9f32df5c4ec2cc3e63bb153cb Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Tue, 10 Nov 2020 13:13:57 -0800 Subject: [PATCH 04/21] Complete functionality Signed-off-by: John Shepherd --- src/gui/plugins/tape_measure/TapeMeasure.cc | 194 ++++++++++++++----- src/gui/plugins/tape_measure/TapeMeasure.hh | 10 + src/gui/plugins/tape_measure/TapeMeasure.qml | 36 ++++ src/gui/plugins/tape_measure/TapeMeasure.qrc | 1 + src/gui/plugins/tape_measure/trashcan.png | Bin 0 -> 1256 bytes 5 files changed, 192 insertions(+), 49 deletions(-) create mode 100644 src/gui/plugins/tape_measure/trashcan.png diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index ec5169474a..582e983b42 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -51,6 +51,26 @@ namespace ignition::gazebo public: std::mutex mutex; public: bool measure = false; + + public: int startPointId = 1; + + public: int endPointId = 2; + + public: ignition::math::Vector3d startPoint = ignition::math::Vector3d::Zero; + public: ignition::math::Vector3d endPoint = ignition::math::Vector3d::Zero; + + public: ignition::math::Vector4d hoverColor = ignition::math::Vector4d(0.2, 0.2, 0.2, 0.5); + public: ignition::math::Vector4d drawColor = ignition::math::Vector4d(0.2, 0.2, 0.2, 1.0); + + public: std::unordered_set placedMarkers; + + public: int lineId = 3; + + public: int currentId = startPointId; + + public: double distance = 0.0; + + public: bool placed = false; }; } @@ -80,9 +100,109 @@ void TapeMeasure::LoadConfig(const tinyxml2::XMLElement *) ///////////////////////////////////////////////// void TapeMeasure::OnMeasure() { + this->Reset(); this->dataPtr->measure = true; } +///////////////////////////////////////////////// +void TapeMeasure::OnReset() +{ + this->Reset(); +} + +void TapeMeasure::Reset() +{ + this->dataPtr->currentId = this->dataPtr->startPointId; + this->dataPtr->startPoint = ignition::math::Vector3d::Zero; + this->dataPtr->endPoint = ignition::math::Vector3d::Zero; + this->dataPtr->placedMarkers.clear(); + this->dataPtr->distance = 0.0; + this->newDistance(); + + if (this->dataPtr->placed) + { + // Delete the previously created marker + ignition::msgs::Marker markerMsg; + markerMsg.set_action(ignition::msgs::Marker::DELETE_ALL); + this->dataPtr->node.Request("/marker", markerMsg); + this->dataPtr->placed = false; + } +} + +double TapeMeasure::Distance() +{ + return this->dataPtr->distance; +} + +void TapeMeasure::DrawPoint(int id, math::Vector3d &_point, math::Vector4d &_color) +{ + ignition::msgs::Marker markerMsg; + if (this->dataPtr->placedMarkers.find(id) != this->dataPtr->placedMarkers.end()) + { + // Delete the previously created marker + markerMsg.set_ns("default"); + markerMsg.set_id(id); + markerMsg.set_action(ignition::msgs::Marker::DELETE_MARKER); + this->dataPtr->node.Request("/marker", markerMsg); + } + else + { + this->dataPtr->placedMarkers.insert(id); + } + + markerMsg.set_ns("default"); + markerMsg.set_id(id); + markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); + markerMsg.set_type(ignition::msgs::Marker::SPHERE); + ignition::msgs::Set(markerMsg.mutable_scale(), + ignition::math::Vector3d(0.1, 0.1, 0.1)); + markerMsg.mutable_material()->mutable_ambient()->set_r(_color[0]); + markerMsg.mutable_material()->mutable_ambient()->set_g(_color[1]); + markerMsg.mutable_material()->mutable_ambient()->set_b(_color[2]); + markerMsg.mutable_material()->mutable_ambient()->set_a(_color[3]); + markerMsg.mutable_material()->mutable_diffuse()->set_r(_color[0]); + markerMsg.mutable_material()->mutable_diffuse()->set_g(_color[1]); + markerMsg.mutable_material()->mutable_diffuse()->set_b(_color[2]); + markerMsg.mutable_material()->mutable_diffuse()->set_a(_color[3]); + ignition::msgs::Set(markerMsg.mutable_pose(), + ignition::math::Pose3d(_point.X(), _point.Y(), _point.Z(), 0, 0, 0)); + this->dataPtr->node.Request("/marker", markerMsg); +} + +void TapeMeasure::DrawLine(int id, math::Vector3d &_startPoint, math::Vector3d &_endPoint, math::Vector4d &_color) +{ + ignition::msgs::Marker markerMsg; + if (this->dataPtr->placedMarkers.find(id) != this->dataPtr->placedMarkers.end()) + { + // Delete the previously created marker + markerMsg.set_ns("default"); + markerMsg.set_id(id); + markerMsg.set_action(ignition::msgs::Marker::DELETE_MARKER); + this->dataPtr->node.Request("/marker", markerMsg); + } + else + { + this->dataPtr->placedMarkers.insert(id); + } + + markerMsg.set_ns("default"); + markerMsg.set_id(id); + markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); + markerMsg.set_type(ignition::msgs::Marker::LINE_LIST); + markerMsg.mutable_material()->mutable_ambient()->set_r(_color[0]); + markerMsg.mutable_material()->mutable_ambient()->set_g(_color[1]); + markerMsg.mutable_material()->mutable_ambient()->set_b(_color[2]); + markerMsg.mutable_material()->mutable_ambient()->set_a(_color[3]); + markerMsg.mutable_material()->mutable_diffuse()->set_r(_color[0]); + markerMsg.mutable_material()->mutable_diffuse()->set_g(_color[1]); + markerMsg.mutable_material()->mutable_diffuse()->set_b(_color[2]); + markerMsg.mutable_material()->mutable_diffuse()->set_a(_color[3]); + ignition::msgs::Set(markerMsg.add_point(), _startPoint); + ignition::msgs::Set(markerMsg.add_point(), _endPoint); + + this->dataPtr->node.Request("/marker", markerMsg); +} + bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) { if (_event->type() == ignition::gazebo::gui::events::HoverToScene::kType) @@ -94,32 +214,16 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) // rendering calls here if (this->dataPtr->measure && hoverToSceneEvent) { - // Delete the previously created marker - ignition::msgs::Marker markerMsg; - markerMsg.set_ns("default"); - markerMsg.set_id(1); - markerMsg.set_action(ignition::msgs::Marker::DELETE_MARKER); - this->dataPtr->node.Request("/marker", markerMsg); - math::Vector3d point = hoverToSceneEvent->Point(); - markerMsg.set_ns("default"); - markerMsg.set_id(1); - markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); - markerMsg.set_type(ignition::msgs::Marker::SPHERE); - ignition::msgs::Set(markerMsg.mutable_scale(), - ignition::math::Vector3d(0.1, 0.1, 0.1)); - markerMsg.mutable_material()->mutable_ambient()->set_r(0.2); - markerMsg.mutable_material()->mutable_ambient()->set_g(0.2); - markerMsg.mutable_material()->mutable_ambient()->set_b(1); - markerMsg.mutable_material()->mutable_ambient()->set_a(1); - markerMsg.mutable_material()->mutable_diffuse()->set_r(0.2); - markerMsg.mutable_material()->mutable_diffuse()->set_g(0.2); - markerMsg.mutable_material()->mutable_diffuse()->set_b(1); - markerMsg.mutable_material()->mutable_diffuse()->set_a(1); - ignition::msgs::Set(markerMsg.mutable_pose(), - ignition::math::Pose3d(point.X(), point.Y(), point.Z(), 0, 0, 0)); - this->dataPtr->node.Request("/marker", markerMsg); + this->DrawPoint(this->dataPtr->currentId, point, this->dataPtr->hoverColor); + if (this->dataPtr->currentId == this->dataPtr->endPointId) + { + this->DrawLine(this->dataPtr->lineId, this->dataPtr->startPoint, point, this->dataPtr->hoverColor); + this->dataPtr->distance = this->dataPtr->startPoint.Distance(point); + this->newDistance(); + } } + this->dataPtr->placed = true; } // Note: the following isn't an else if statement due to the hover scene // event sometimes smothering this click event if the logic uses an else if @@ -134,32 +238,24 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) if (this->dataPtr->measure && leftClickToSceneEvent) { math::Vector3d point = leftClickToSceneEvent->Point(); - // Delete the previously created marker - ignition::msgs::Marker markerMsg; - markerMsg.set_ns("default"); - markerMsg.set_id(1); - markerMsg.set_action(ignition::msgs::Marker::DELETE_MARKER); - this->dataPtr->node.Request("/marker", markerMsg); - - markerMsg.set_ns("default"); - markerMsg.set_id(1); - markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); - markerMsg.set_type(ignition::msgs::Marker::SPHERE); - ignition::msgs::Set(markerMsg.mutable_scale(), - ignition::math::Vector3d(0.1, 0.1, 0.1)); - markerMsg.mutable_material()->mutable_ambient()->set_r(0); - markerMsg.mutable_material()->mutable_ambient()->set_g(0); - markerMsg.mutable_material()->mutable_ambient()->set_b(1); - markerMsg.mutable_material()->mutable_ambient()->set_a(1); - markerMsg.mutable_material()->mutable_diffuse()->set_r(0); - markerMsg.mutable_material()->mutable_diffuse()->set_g(0); - markerMsg.mutable_material()->mutable_diffuse()->set_b(1); - markerMsg.mutable_material()->mutable_diffuse()->set_a(1); - ignition::msgs::Set(markerMsg.mutable_pose(), - ignition::math::Pose3d(point.X(), point.Y(), point.Z(), 0, 0, 0)); - this->dataPtr->node.Request("/marker", markerMsg); - this->dataPtr->measure = false; + this->DrawPoint(this->dataPtr->currentId, point, this->dataPtr->drawColor); + // If we just placed the end point, end execution + if (this->dataPtr->currentId == this->dataPtr->startPointId) + { + this->dataPtr->startPoint = point; + } + else + { + this->dataPtr->endPoint = point; + this->dataPtr->measure = false; + this->DrawLine(this->dataPtr->lineId, this->dataPtr->startPoint, this->dataPtr->endPoint, this->dataPtr->drawColor); + ignwarn << "Distance is " << this->dataPtr->startPoint.Distance(this->dataPtr->endPoint) << "\n"; + this->dataPtr->distance = this->dataPtr->startPoint.Distance(this->dataPtr->endPoint); + this->newDistance(); + } + this->dataPtr->currentId = this->dataPtr->endPointId; } + this->dataPtr->placed = true; } return QObject::eventFilter(_obj, _event); diff --git a/src/gui/plugins/tape_measure/TapeMeasure.hh b/src/gui/plugins/tape_measure/TapeMeasure.hh index 8abb154d06..adf4d4b661 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.hh +++ b/src/gui/plugins/tape_measure/TapeMeasure.hh @@ -21,6 +21,8 @@ #include #include +#include +#include namespace ignition { @@ -46,10 +48,18 @@ namespace gazebo public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override; public slots: void OnMeasure(); + public slots: void OnReset(); + public slots: double Distance(); + public: void Reset(); + + public: void DrawPoint(int id, ignition::math::Vector3d &_point, ignition::math::Vector4d &_color); + public: void DrawLine(int id, ignition::math::Vector3d &_startPoint, ignition::math::Vector3d &_endPoint, ignition::math::Vector4d &_color); // Documentation inherited protected: bool eventFilter(QObject *_obj, QEvent *_event) override; + signals: void newDistance(); + /// \internal /// \brief Pointer to private data. private: std::unique_ptr dataPtr; diff --git a/src/gui/plugins/tape_measure/TapeMeasure.qml b/src/gui/plugins/tape_measure/TapeMeasure.qml index 98fac16636..7e2140b045 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.qml +++ b/src/gui/plugins/tape_measure/TapeMeasure.qml @@ -36,6 +36,19 @@ ToolBar { Material.color(Material.Grey, Material.Shade800) : Material.color(Material.Grey, Material.Shade100) + property var distance: 0.0 + + function updateDistance() { + distance = TapeMeasure.Distance(); + } + + Connections { + target: TapeMeasure + onNewDistance: { + updateDistance(); + } + } + background: Rectangle { color: "transparent" } @@ -66,5 +79,28 @@ ToolBar { TapeMeasure.OnMeasure(); } } + ToolButton { + id: reset + checkable: true + checked: true + ButtonGroup.group: group + ToolTip.text: "Reset measurement" + ToolTip.visible: hovered + ToolTip.delay: Qt.styleHints.mousePressAndHoldInterval + contentItem: Image { + fillMode: Image.Pad + horizontalAlignment: Image.AlignHCenter + verticalAlignment: Image.AlignVCenter + source: "trashcan.png" + sourceSize.width: 24; + sourceSize.height: 24; + } + onClicked: { + TapeMeasure.OnReset(); + } + } + Text { + text: qsTr(" Distance (m): " + distance.toFixed(3)) + } } } diff --git a/src/gui/plugins/tape_measure/TapeMeasure.qrc b/src/gui/plugins/tape_measure/TapeMeasure.qrc index b4f504c64f..260b68f734 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.qrc +++ b/src/gui/plugins/tape_measure/TapeMeasure.qrc @@ -2,5 +2,6 @@ TapeMeasure.qml tape_measure.svg + trashcan.png diff --git a/src/gui/plugins/tape_measure/trashcan.png b/src/gui/plugins/tape_measure/trashcan.png new file mode 100644 index 0000000000000000000000000000000000000000..6ea9ed48a5cb727a2645b293fdb821c59f71039e GIT binary patch literal 1256 zcmeAS@N?(olHy`uVBq!ia0y~yU~~iGDI9D-5l_YLD?o~~z$3Dlfk96hgc&QA+Lr+Z zB}-f*N`mv#O3D+9QW+dm@{>{(JaZG%Q-e|yQz{EjrrIztu#|ebIEGZ*dUO3CZyP{rqesevdE6?vOb1TFv z^2~*On>iU;1RW$8i6R&hSp?iLi46bk>s}|dIZJ$sIa`o%-bUYe%lh-ivlz=B9)G6A ztI)%6hyzY!Fk$M)W+qsSSa$){VK<}U*q2H*V}_cNtzp^>JG_`Vlp73~h#t4#AVg Date: Tue, 10 Nov 2020 16:47:21 -0800 Subject: [PATCH 05/21] Tidy up Signed-off-by: John Shepherd --- src/gui/plugins/tape_measure/TapeMeasure.cc | 137 ++++++++++++-------- src/gui/plugins/tape_measure/TapeMeasure.hh | 43 +++++- 2 files changed, 123 insertions(+), 57 deletions(-) diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index 582e983b42..8db9b5cefd 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2020 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -47,30 +47,55 @@ namespace ignition::gazebo /// \brief Ignition communication node. public: transport::Node node; - /// \brief Mutex to protect mode + /// \brief Mutex to protect mode. public: std::mutex mutex; + /// \brief True if currently measure, else false. public: bool measure = false; + /// \brief The id of the start point marker. public: int startPointId = 1; + /// \brief The id of the end point marker. public: int endPointId = 2; - public: ignition::math::Vector3d startPoint = ignition::math::Vector3d::Zero; - public: ignition::math::Vector3d endPoint = ignition::math::Vector3d::Zero; + /// \brief The id of the line marker. + public: int lineId = 3; - public: ignition::math::Vector4d hoverColor = ignition::math::Vector4d(0.2, 0.2, 0.2, 0.5); - public: ignition::math::Vector4d drawColor = ignition::math::Vector4d(0.2, 0.2, 0.2, 1.0); + /// \brief The id of the start or end point marker that is currently + /// being placed. This is primarily used to track the state machine of + /// the plugin. + public: int currentId = startPointId; - public: std::unordered_set placedMarkers; + /// \brief The location of the placed starting point of the tape measure + /// tool, only set when the user clicks to set the point. + public: ignition::math::Vector3d startPoint = + ignition::math::Vector3d::Zero; - public: int lineId = 3; + /// \brief The location of the placed ending point of the tape measure + /// tool, only set when the user clicks to set the point. + public: ignition::math::Vector3d endPoint = ignition::math::Vector3d::Zero; - public: int currentId = startPointId; + /// \brief The color to set the marker when hovering the mouse over the + /// scene. + public: ignition::math::Vector4d hoverColor = + ignition::math::Vector4d(0.2, 0.2, 0.2, 0.5); + + /// \brief The color to draw the marker when the user clicks to confirm + /// its location. + public: ignition::math::Vector4d drawColor = + ignition::math::Vector4d(0.2, 0.2, 0.2, 1.0); + + /// \brief A set of the currently placed markers. Used to make sure a + /// non-existent marker is not deleted. + public: std::unordered_set placedMarkers; + /// \brief The current distance between the two points. This distance + /// is updated as the user hovers the end point as well. public: double distance = 0.0; - public: bool placed = false; + /// \brief The namespace that the markers for this plugin are placed in. + public: std::string ns = "tape_measure"; }; } @@ -110,52 +135,59 @@ void TapeMeasure::OnReset() this->Reset(); } +///////////////////////////////////////////////// void TapeMeasure::Reset() { + this->DeleteMarker(this->dataPtr->startPointId); + this->DeleteMarker(this->dataPtr->endPointId); + this->DeleteMarker(this->dataPtr->lineId); + this->dataPtr->currentId = this->dataPtr->startPointId; this->dataPtr->startPoint = ignition::math::Vector3d::Zero; this->dataPtr->endPoint = ignition::math::Vector3d::Zero; this->dataPtr->placedMarkers.clear(); this->dataPtr->distance = 0.0; this->newDistance(); - - if (this->dataPtr->placed) - { - // Delete the previously created marker - ignition::msgs::Marker markerMsg; - markerMsg.set_action(ignition::msgs::Marker::DELETE_ALL); - this->dataPtr->node.Request("/marker", markerMsg); - this->dataPtr->placed = false; - } } +///////////////////////////////////////////////// double TapeMeasure::Distance() { return this->dataPtr->distance; } -void TapeMeasure::DrawPoint(int id, math::Vector3d &_point, math::Vector4d &_color) +///////////////////////////////////////////////// +void TapeMeasure::DeleteMarker(int _id) { ignition::msgs::Marker markerMsg; - if (this->dataPtr->placedMarkers.find(id) != this->dataPtr->placedMarkers.end()) + if (this->dataPtr->placedMarkers.find(_id) != + this->dataPtr->placedMarkers.end()) { // Delete the previously created marker - markerMsg.set_ns("default"); - markerMsg.set_id(id); + markerMsg.set_ns(this->dataPtr->ns); + markerMsg.set_id(_id); markerMsg.set_action(ignition::msgs::Marker::DELETE_MARKER); this->dataPtr->node.Request("/marker", markerMsg); } else { - this->dataPtr->placedMarkers.insert(id); + this->dataPtr->placedMarkers.insert(_id); } +} - markerMsg.set_ns("default"); - markerMsg.set_id(id); +///////////////////////////////////////////////// +void TapeMeasure::DrawPoint(int _id, + math::Vector3d &_point, math::Vector4d &_color) +{ + this->DeleteMarker(_id); + + ignition::msgs::Marker markerMsg; + markerMsg.set_ns(this->dataPtr->ns); + markerMsg.set_id(_id); markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); markerMsg.set_type(ignition::msgs::Marker::SPHERE); ignition::msgs::Set(markerMsg.mutable_scale(), - ignition::math::Vector3d(0.1, 0.1, 0.1)); + ignition::math::Vector3d(0.1, 0.1, 0.1)); markerMsg.mutable_material()->mutable_ambient()->set_r(_color[0]); markerMsg.mutable_material()->mutable_ambient()->set_g(_color[1]); markerMsg.mutable_material()->mutable_ambient()->set_b(_color[2]); @@ -165,28 +197,19 @@ void TapeMeasure::DrawPoint(int id, math::Vector3d &_point, math::Vector4d &_col markerMsg.mutable_material()->mutable_diffuse()->set_b(_color[2]); markerMsg.mutable_material()->mutable_diffuse()->set_a(_color[3]); ignition::msgs::Set(markerMsg.mutable_pose(), - ignition::math::Pose3d(_point.X(), _point.Y(), _point.Z(), 0, 0, 0)); + ignition::math::Pose3d(_point.X(), _point.Y(), _point.Z(), 0, 0, 0)); this->dataPtr->node.Request("/marker", markerMsg); } -void TapeMeasure::DrawLine(int id, math::Vector3d &_startPoint, math::Vector3d &_endPoint, math::Vector4d &_color) +///////////////////////////////////////////////// +void TapeMeasure::DrawLine(int _id, math::Vector3d &_startPoint, + math::Vector3d &_endPoint, math::Vector4d &_color) { - ignition::msgs::Marker markerMsg; - if (this->dataPtr->placedMarkers.find(id) != this->dataPtr->placedMarkers.end()) - { - // Delete the previously created marker - markerMsg.set_ns("default"); - markerMsg.set_id(id); - markerMsg.set_action(ignition::msgs::Marker::DELETE_MARKER); - this->dataPtr->node.Request("/marker", markerMsg); - } - else - { - this->dataPtr->placedMarkers.insert(id); - } + this->DeleteMarker(_id); - markerMsg.set_ns("default"); - markerMsg.set_id(id); + ignition::msgs::Marker markerMsg; + markerMsg.set_ns(this->dataPtr->ns); + markerMsg.set_id(_id); markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); markerMsg.set_type(ignition::msgs::Marker::LINE_LIST); markerMsg.mutable_material()->mutable_ambient()->set_r(_color[0]); @@ -203,6 +226,7 @@ void TapeMeasure::DrawLine(int id, math::Vector3d &_startPoint, math::Vector3d & this->dataPtr->node.Request("/marker", markerMsg); } +///////////////////////////////////////////////// bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) { if (_event->type() == ignition::gazebo::gui::events::HoverToScene::kType) @@ -215,15 +239,19 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) if (this->dataPtr->measure && hoverToSceneEvent) { math::Vector3d point = hoverToSceneEvent->Point(); - this->DrawPoint(this->dataPtr->currentId, point, this->dataPtr->hoverColor); + this->DrawPoint(this->dataPtr->currentId, point, + this->dataPtr->hoverColor); + + // If the user is currently choosing the end point, draw the connecting + // line and update the new distance. if (this->dataPtr->currentId == this->dataPtr->endPointId) { - this->DrawLine(this->dataPtr->lineId, this->dataPtr->startPoint, point, this->dataPtr->hoverColor); + this->DrawLine(this->dataPtr->lineId, this->dataPtr->startPoint, + point, this->dataPtr->hoverColor); this->dataPtr->distance = this->dataPtr->startPoint.Distance(point); this->newDistance(); } } - this->dataPtr->placed = true; } // Note: the following isn't an else if statement due to the hover scene // event sometimes smothering this click event if the logic uses an else if @@ -238,24 +266,27 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) if (this->dataPtr->measure && leftClickToSceneEvent) { math::Vector3d point = leftClickToSceneEvent->Point(); - this->DrawPoint(this->dataPtr->currentId, point, this->dataPtr->drawColor); - // If we just placed the end point, end execution + this->DrawPoint(this->dataPtr->currentId, point, + this->dataPtr->drawColor); + // If the user is placing the start point, update its position if (this->dataPtr->currentId == this->dataPtr->startPointId) { this->dataPtr->startPoint = point; } + // If the user is placing the end point, update the end position, + // end the measurement state, and update the draw line and distance else { this->dataPtr->endPoint = point; this->dataPtr->measure = false; - this->DrawLine(this->dataPtr->lineId, this->dataPtr->startPoint, this->dataPtr->endPoint, this->dataPtr->drawColor); - ignwarn << "Distance is " << this->dataPtr->startPoint.Distance(this->dataPtr->endPoint) << "\n"; - this->dataPtr->distance = this->dataPtr->startPoint.Distance(this->dataPtr->endPoint); + this->DrawLine(this->dataPtr->lineId, this->dataPtr->startPoint, + this->dataPtr->endPoint, this->dataPtr->drawColor); + this->dataPtr->distance = + this->dataPtr->startPoint.Distance(this->dataPtr->endPoint); this->newDistance(); } this->dataPtr->currentId = this->dataPtr->endPointId; } - this->dataPtr->placed = true; } return QObject::eventFilter(_obj, _event); diff --git a/src/gui/plugins/tape_measure/TapeMeasure.hh b/src/gui/plugins/tape_measure/TapeMeasure.hh index adf4d4b661..71a0f67faf 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.hh +++ b/src/gui/plugins/tape_measure/TapeMeasure.hh @@ -47,17 +47,52 @@ namespace gazebo // Documentation inherited public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override; + /// \brief Deletes the marker with the provided id within the + /// "tape_measure" namespace. + /// \param[in] _id The id of the marker + public: void DeleteMarker(int _id); + + /// \brief Resets all of the relevant data for this plugin. Called when + /// the user clicks the reset button and when the user starts a new + /// measurement. + public: void Reset(); + + /// \brief Draws a point marker. Called to display the start and end + /// point of the tape measure. + /// \param[in] _id The id of the marker + /// \param[in] _point The x, y, z coordinates of where to place the marker + /// \param[in] _color The rgba color to set the marker + public: void DrawPoint(int _id, + ignition::math::Vector3d &_point, + ignition::math::Vector4d &_color); + + /// \brief Draws a line marker. Called to display the line between the + /// start and end point of the tape measure. + /// \param[in] _id The id of the marker + /// \param[in] _startPoint The x, y, z coordinates of the line start point + /// \param[in] _endPoint The x, y, z coordinates of the line end point + /// \param[in] _color The rgba color to set the marker + public: void DrawLine(int _id, + ignition::math::Vector3d &_startPoint, + ignition::math::Vector3d &_endPoint, + ignition::math::Vector4d &_color); + + /// \brief Callback in Qt thread when the new measurement button is + /// clicked. public slots: void OnMeasure(); + + /// \brief Callback in Qt thread when the reset button is clicked. public slots: void OnReset(); - public slots: double Distance(); - public: void Reset(); - public: void DrawPoint(int id, ignition::math::Vector3d &_point, ignition::math::Vector4d &_color); - public: void DrawLine(int id, ignition::math::Vector3d &_startPoint, ignition::math::Vector3d &_endPoint, ignition::math::Vector4d &_color); + /// \brief Callback in Qt thread to get the distance to display in the + /// gui window. + /// \return The distance between the start and end point of the measurement + public slots: double Distance(); // Documentation inherited protected: bool eventFilter(QObject *_obj, QEvent *_event) override; + /// \brief Signal fired when a new tape measure distance is set. signals: void newDistance(); /// \internal From 041e54bf5c9031b24a9bf1407d7dcebe006d9567 Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Tue, 10 Nov 2020 17:02:49 -0800 Subject: [PATCH 06/21] Update docs Signed-off-by: John Shepherd --- include/ignition/gazebo/gui/GuiEvents.hh | 18 ++++++++++-------- src/gui/plugins/tape_measure/TapeMeasure.hh | 5 +---- 2 files changed, 11 insertions(+), 12 deletions(-) diff --git a/include/ignition/gazebo/gui/GuiEvents.hh b/include/ignition/gazebo/gui/GuiEvents.hh index e8a87e2ba4..3f3389e8a8 100644 --- a/include/ignition/gazebo/gui/GuiEvents.hh +++ b/include/ignition/gazebo/gui/GuiEvents.hh @@ -211,12 +211,13 @@ namespace events std::string filePath; }; - /// \brief Event called which broadcasts the 3D coordinates of a user's + /// \brief Event which is called to broadcast the 3D coordinates of a user's /// mouse hover within the scene. class HoverToScene : public QEvent { /// \brief Constructor - /// \param[in] _filePath The path to an SDF file. + /// \param[in] _point The point at which the mouse is hovering within the + /// scene public: explicit HoverToScene(const math::Vector3d &_point) : QEvent(kType), point(_point) { @@ -225,23 +226,24 @@ namespace events /// \brief Unique type for this event. static const QEvent::Type kType = QEvent::Type(QEvent::User + 6); - /// \brief Get the point within the scene that the user clicked. - /// \return The 3D point. + /// \brief Get the point within the scene over which the user is hovering. + /// \return The 3D point public: math::Vector3d Point() const { return this->point; } - /// \brief The 3D point that the user clicked. + /// \brief The 3D point over which the user is hovering. private: math::Vector3d point; }; - /// \brief Event called which broadcasts the 3D coordinates of a user's + /// \brief Event which is called to broadcast the 3D coordinates of a user's /// left click within the scene. class LeftClickToScene : public QEvent { /// \brief Constructor - /// \param[in] _filePath The path to an SDF file. + /// \param[in] _point The point which the user has left clicked within the + /// scene public: explicit LeftClickToScene(const math::Vector3d &_point) : QEvent(kType), point(_point) { @@ -257,7 +259,7 @@ namespace events return this->point; } - /// \brief The 3D point that the user clicked. + /// \brief The 3D point that the user clicked within the scene. private: math::Vector3d point; }; } // namespace events diff --git a/src/gui/plugins/tape_measure/TapeMeasure.hh b/src/gui/plugins/tape_measure/TapeMeasure.hh index 71a0f67faf..12890ff45d 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.hh +++ b/src/gui/plugins/tape_measure/TapeMeasure.hh @@ -30,10 +30,7 @@ namespace gazebo { class TapeMeasurePrivate; - /// \brief Provides buttons for translation, rotation, and scale - /// - /// ## Configuration - /// \ : Set the service to receive transform mode requests. + /// \brief Provides buttons for the tape measure tool. class TapeMeasure : public ignition::gui::Plugin { Q_OBJECT From 22d1c0f054d55f8e4b1e568e762069935b9ffb28 Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Tue, 10 Nov 2020 17:14:16 -0800 Subject: [PATCH 07/21] Clean up Signed-off-by: John Shepherd --- src/gui/plugins/scene3d/Scene3D.cc | 8 +++++-- src/gui/plugins/tape_measure/CMakeLists.txt | 2 -- src/gui/plugins/tape_measure/TapeMeasure.cc | 24 ++++++--------------- 3 files changed, 12 insertions(+), 22 deletions(-) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 36237e1fc6..004890f16f 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -772,6 +772,7 @@ void IgnRenderer::HandleMouseEvent() this->HandleMouseViewControl(); } +///////////////////////////////////////////////// void IgnRenderer::BroadcastHoverPos() { if (this->dataPtr->hoverDirty) @@ -785,6 +786,7 @@ void IgnRenderer::BroadcastHoverPos() } } +///////////////////////////////////////////////// void IgnRenderer::BroadcastLeftClick() { if (this->dataPtr->mouseEvent.Button() == common::MouseEvent::LEFT && @@ -1861,14 +1863,16 @@ math::Vector3d IgnRenderer::ScreenToScene( math::Vector3d point; if (result) + { point = result.point; + } + // Set point to be 10m away if no intersection found else { - point = this->dataPtr->rayQuery->Origin() + + point = this->dataPtr->rayQuery->Origin() + this->dataPtr->rayQuery->Direction() * 10; } - // Set point to be 10m away if no intersection found return point; } diff --git a/src/gui/plugins/tape_measure/CMakeLists.txt b/src/gui/plugins/tape_measure/CMakeLists.txt index 4b8869c9a8..4b5322fc2a 100644 --- a/src/gui/plugins/tape_measure/CMakeLists.txt +++ b/src/gui/plugins/tape_measure/CMakeLists.txt @@ -4,5 +4,3 @@ gz_add_gui_plugin(TapeMeasure PRIVATE_LINK_LIBS ${IGNITION-RENDERING_LIBRARIES} ) - - diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index 8db9b5cefd..364444bb72 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -14,8 +14,6 @@ * limitations under the License. * */ -#include -#include #include #include @@ -25,17 +23,7 @@ #include #include #include -#include -#include -#include -#include -#include -#include -#include - -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParentEntity.hh" -#include "ignition/gazebo/EntityComponentManager.hh" + #include "ignition/gazebo/gui/GuiEvents.hh" #include "TapeMeasure.hh" @@ -177,7 +165,7 @@ void TapeMeasure::DeleteMarker(int _id) ///////////////////////////////////////////////// void TapeMeasure::DrawPoint(int _id, - math::Vector3d &_point, math::Vector4d &_color) + ignition::math::Vector3d &_point, ignition::math::Vector4d &_color) { this->DeleteMarker(_id); @@ -202,8 +190,8 @@ void TapeMeasure::DrawPoint(int _id, } ///////////////////////////////////////////////// -void TapeMeasure::DrawLine(int _id, math::Vector3d &_startPoint, - math::Vector3d &_endPoint, math::Vector4d &_color) +void TapeMeasure::DrawLine(int _id, ignition::math::Vector3d &_startPoint, + ignition::math::Vector3d &_endPoint, ignition::math::Vector4d &_color) { this->DeleteMarker(_id); @@ -238,7 +226,7 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) // rendering calls here if (this->dataPtr->measure && hoverToSceneEvent) { - math::Vector3d point = hoverToSceneEvent->Point(); + ignition::math::Vector3d point = hoverToSceneEvent->Point(); this->DrawPoint(this->dataPtr->currentId, point, this->dataPtr->hoverColor); @@ -265,7 +253,7 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) // rendering calls here if (this->dataPtr->measure && leftClickToSceneEvent) { - math::Vector3d point = leftClickToSceneEvent->Point(); + ignition::math::Vector3d point = leftClickToSceneEvent->Point(); this->DrawPoint(this->dataPtr->currentId, point, this->dataPtr->drawColor); // If the user is placing the start point, update its position From f0b022ab18cf42ebe76c4357da984baa8cdae836 Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Tue, 10 Nov 2020 17:17:58 -0800 Subject: [PATCH 08/21] revert some changes Signed-off-by: John Shepherd --- src/gui/plugins/scene3d/Scene3D.cc | 14 +++----------- 1 file changed, 3 insertions(+), 11 deletions(-) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 004890f16f..04eed96d82 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -1860,20 +1860,12 @@ math::Vector3d IgnRenderer::ScreenToScene( this->dataPtr->camera, math::Vector2d(nx, ny)); auto result = this->dataPtr->rayQuery->ClosestPoint(); - math::Vector3d point; - if (result) - { - point = result.point; - } + return result.point; + // Set point to be 10m away if no intersection found - else - { - point = this->dataPtr->rayQuery->Origin() + + return this->dataPtr->rayQuery->Origin() + this->dataPtr->rayQuery->Direction() * 10; - } - - return point; } //////////////////////////////////////////////// From 0dfec2fbf0b200236840f22b007a156b7f1e46ca Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Tue, 10 Nov 2020 17:38:51 -0800 Subject: [PATCH 09/21] Add crosshair cursor Signed-off-by: John Shepherd --- src/gui/plugins/tape_measure/TapeMeasure.cc | 37 ++++++++++----------- src/gui/plugins/tape_measure/TapeMeasure.hh | 3 -- 2 files changed, 17 insertions(+), 23 deletions(-) diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index 364444bb72..ee6e431eb7 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -35,9 +35,6 @@ namespace ignition::gazebo /// \brief Ignition communication node. public: transport::Node node; - /// \brief Mutex to protect mode. - public: std::mutex mutex; - /// \brief True if currently measure, else false. public: bool measure = false; @@ -115,6 +112,7 @@ void TapeMeasure::OnMeasure() { this->Reset(); this->dataPtr->measure = true; + QGuiApplication::setOverrideCursor(Qt::CrossCursor); } ///////////////////////////////////////////////// @@ -135,7 +133,9 @@ void TapeMeasure::Reset() this->dataPtr->endPoint = ignition::math::Vector3d::Zero; this->dataPtr->placedMarkers.clear(); this->dataPtr->distance = 0.0; + this->dataPtr->measure = false; this->newDistance(); + QGuiApplication::restoreOverrideCursor(); } ///////////////////////////////////////////////// @@ -147,20 +147,16 @@ double TapeMeasure::Distance() ///////////////////////////////////////////////// void TapeMeasure::DeleteMarker(int _id) { - ignition::msgs::Marker markerMsg; - if (this->dataPtr->placedMarkers.find(_id) != + if (this->dataPtr->placedMarkers.find(_id) == this->dataPtr->placedMarkers.end()) - { - // Delete the previously created marker - markerMsg.set_ns(this->dataPtr->ns); - markerMsg.set_id(_id); - markerMsg.set_action(ignition::msgs::Marker::DELETE_MARKER); - this->dataPtr->node.Request("/marker", markerMsg); - } - else - { - this->dataPtr->placedMarkers.insert(_id); - } + return; + + // Delete the previously created marker + ignition::msgs::Marker markerMsg; + markerMsg.set_ns(this->dataPtr->ns); + markerMsg.set_id(_id); + markerMsg.set_action(ignition::msgs::Marker::DELETE_MARKER); + this->dataPtr->node.Request("/marker", markerMsg); } ///////////////////////////////////////////////// @@ -168,6 +164,7 @@ void TapeMeasure::DrawPoint(int _id, ignition::math::Vector3d &_point, ignition::math::Vector4d &_color) { this->DeleteMarker(_id); + this->dataPtr->placedMarkers.insert(_id); ignition::msgs::Marker markerMsg; markerMsg.set_ns(this->dataPtr->ns); @@ -186,6 +183,7 @@ void TapeMeasure::DrawPoint(int _id, markerMsg.mutable_material()->mutable_diffuse()->set_a(_color[3]); ignition::msgs::Set(markerMsg.mutable_pose(), ignition::math::Pose3d(_point.X(), _point.Y(), _point.Z(), 0, 0, 0)); + this->dataPtr->node.Request("/marker", markerMsg); } @@ -194,6 +192,7 @@ void TapeMeasure::DrawLine(int _id, ignition::math::Vector3d &_startPoint, ignition::math::Vector3d &_endPoint, ignition::math::Vector4d &_color) { this->DeleteMarker(_id); + this->dataPtr->placedMarkers.insert(_id); ignition::msgs::Marker markerMsg; markerMsg.set_ns(this->dataPtr->ns); @@ -241,10 +240,7 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) } } } - // Note: the following isn't an else if statement due to the hover scene - // event sometimes smothering this click event if the logic uses an else if - // statement - if (_event->type() == ignition::gazebo::gui::events::LeftClickToScene::kType) + else if (_event->type() == ignition::gazebo::gui::events::LeftClickToScene::kType) { auto leftClickToSceneEvent = reinterpret_cast(_event); @@ -272,6 +268,7 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) this->dataPtr->distance = this->dataPtr->startPoint.Distance(this->dataPtr->endPoint); this->newDistance(); + QGuiApplication::restoreOverrideCursor(); } this->dataPtr->currentId = this->dataPtr->endPointId; } diff --git a/src/gui/plugins/tape_measure/TapeMeasure.hh b/src/gui/plugins/tape_measure/TapeMeasure.hh index 12890ff45d..9d7baca2b5 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.hh +++ b/src/gui/plugins/tape_measure/TapeMeasure.hh @@ -14,12 +14,9 @@ * limitations under the License. * */ - #ifndef IGNITION_GAZEBO_GUI_TAPEMEASURE_HH_ #define IGNITION_GAZEBO_GUI_TAPEMEASURE_HH_ -#include - #include #include #include From a0f20f6679a2a0543c3153e29d0b481502d37c19 Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Wed, 11 Nov 2020 15:41:08 -0800 Subject: [PATCH 10/21] Add shortcut and new icon Signed-off-by: John Shepherd --- src/gui/plugins/tape_measure/TapeMeasure.qml | 16 +++- src/gui/plugins/tape_measure/TapeMeasure.qrc | 2 +- src/gui/plugins/tape_measure/tape_measure.png | Bin 0 -> 8586 bytes src/gui/plugins/tape_measure/tape_measure.svg | 82 ------------------ 4 files changed, 14 insertions(+), 86 deletions(-) create mode 100644 src/gui/plugins/tape_measure/tape_measure.png delete mode 100644 src/gui/plugins/tape_measure/tape_measure.svg diff --git a/src/gui/plugins/tape_measure/TapeMeasure.qml b/src/gui/plugins/tape_measure/TapeMeasure.qml index 7e2140b045..c9dd482b42 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.qml +++ b/src/gui/plugins/tape_measure/TapeMeasure.qml @@ -42,6 +42,11 @@ ToolBar { distance = TapeMeasure.Distance(); } + function startMeasurement() { + TapeMeasure.OnReset(); + TapeMeasure.OnMeasure(); + } + Connections { target: TapeMeasure onNewDistance: { @@ -57,6 +62,11 @@ ToolBar { id: group } + Shortcut { + sequence: "M" + onActivated: startMeasurement() + } + RowLayout { spacing: 2 ToolButton { @@ -71,9 +81,9 @@ ToolBar { fillMode: Image.Pad horizontalAlignment: Image.AlignHCenter verticalAlignment: Image.AlignVCenter - source: "tape_measure.svg" - sourceSize.width: 24; - sourceSize.height: 24; + source: "tape_measure.png" + sourceSize.width: 36; + sourceSize.height: 36; } onClicked: { TapeMeasure.OnMeasure(); diff --git a/src/gui/plugins/tape_measure/TapeMeasure.qrc b/src/gui/plugins/tape_measure/TapeMeasure.qrc index 260b68f734..e87212d276 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.qrc +++ b/src/gui/plugins/tape_measure/TapeMeasure.qrc @@ -1,7 +1,7 @@ TapeMeasure.qml - tape_measure.svg + tape_measure.png trashcan.png diff --git a/src/gui/plugins/tape_measure/tape_measure.png b/src/gui/plugins/tape_measure/tape_measure.png new file mode 100644 index 0000000000000000000000000000000000000000..228e5834424302df6434ad80b103cd54358a8baa GIT binary patch literal 8586 zcmch7Wmr_v*Y6o(KvF{KmTr)e8bv}<>F!V(1f-NfKt$w6y1N+|x?%2k z@BMJUyw7t#y#M#pIcJ|$XZ`kBYp=a_*lTq~LOg0b000PIDZSJL01Wgk27rr&zL>hv zx&Z(q@apArZSUFr1)ph?u^&B0$XAOmgTt9~z9h5$QLe($do3&?zaW~QPx|7ok*`hy zwf!GWUcHFlv(%-=dfdE%WNW{0#lHG{W$cXpN)X#5aS_FcOiM>JpHp2dZr%7~*6cJ+ z$#fX{-3`r-&4!RD+3V63Ve|pf)_{@_@PrD8B>-N5p-(U&u^`6(_Tm44$p6CJ|A40c zzoQ;Y-nb5986w-y?Ha}cH#kQysx*Ob@Y#->e|G-vV6E@wDreBq(uYGZxFTfnNWG@g}_NaMVgFUUzQur$V zRns8lL75N%^t2(Fa60y2AKX_^!>PLBGCw$`ixvm&n8|G3w$qwi$eSOIlD0Glo>rV7 zJ6ld`sAx8I*xbUI%z^PaPTD?uQ8W8n29#y|M6|Sl6uv;XuznPusOdMy{@kLr65W@R z*8A(zcm8l*N6QP1A0`~5{UQX_Tm(=<@wlFuOjA+Ag4#T}E8#{X5_-%(B}W9d*lFBy z_nj^&)*|8bM$jFQZs8!pn}^zdw-c6 zl`@zIw`0RLoOAs7J#W=eijIOciQj>RpYH_q@v63lEQ0sWSEaOa-E3A}P)nrZiot97-{ceqR6K+@i|o1Y5Yi+Nad5t53Nr%12$9MnoQEoCT!QNQ{0d zYRsP>40Y6fgH_Z;n_0n?=7)9YHlyY54-Ye=`=hyL++NEq{&|hnjBsKbKTsiI;SRZ( z$JfF2Hf^8B)=Ps=b_U-~P8eQ`TlSt#Hp)XRV4E>WB3<3wK0Gx6?DhFwe zKr5#@^4XN)OFx6ghqd}XgOtF=6O_}COqOL-C4Xr``J%e6$q6>hkKk2Zw{W;ELzY&W z``#OK-*(Ri;mL0f;oTYFTc`HpVuaZwpmjDCQB9gjk5IIuuUbvD!4e3sB`tB2;JrV$ z>*hS&3JZ>LYnYgnVu7Aq>Ha)s(Dp9Q-bIqMsH1`yVd2oLSi7|t5O>(~CBn|L@H`~g*k9~S{vo9j0h_Xe^(8Ol}TU@a2hGPG| z{utRrZ+y;F$XyD0_-U+1SX8ZKzOA^;rq$VVLm0Rxr3F3+Oy~BcpsWqe`{*+t^x6Tm z4~^Z4Y1l#)j=jwLmJAGh2%sZjIZI^*?(cXmuoG#Qud;5jVWmMT^!AnO+HVKWSGRO^ z7cm(9Tb-K*V~u|NYOF3Uxc)O$2@2>KfyMe{oLb3F+LB$DV>BCNmU!fZJbqRY9m12H zpewV*vMCV3>ECN2l{jE19+MW-?^)@v$qk4S(>kbbxkwbQm{mN++-aNAXF4yRGh38h z>VE@Y<;^_;hS$09+Sx%2eG^{8vxQR$(Dw#>f97Y>V}q8i2WKKa`4`)l)xcBedbNz>Q;MAn=t@%*02*+jpAd_u zXr@b!tLwAm=cg;Vs?}=&&404J*I4PQYCI# zZE?HrEXsE8KxF&iLh0-O<@#yREa66TcQ{xHU^(d&E)O>um9hoe@Io|BDe z)(Izmau3GlSYV{bj}ShOT$+qRT2XA#++N9|%!XN$hgJKB`z5I#_m8sC>{^X&)je@U=B}+w?o^h`R`7#4(N6s*vn;>Ocji?kEiiG* z`=_haHr8Q1&+Ywkv06kG_ZE&uJJIXqs5T9!f|4>H0?D~oC-gvZ(;W0eb1>EEtJArq zS}qFQsl^nJWsnRpUn?PTg_V74gjUd|4Dgt3TEB1$h9#B?U&$o6J+H0C3{cX(7jymr zhWvuB3^ufGg)bj0^?Nr|yx%lDm*spSu3ayo0hVd}vG{D}pQ87B{?v!Yx!502cJC}2 z;WY<;$?G`9F%F!kS701;`#D##V1d>WFrd#u#jKkjL#1Ra z8$W0~hXr~q9?wwj52+V32>bQk0Mly6%u;AnlYY5%pBfC=z{|hN#Ke?5tf+?IqufW;6@kHtJ4KP_7dV$PV%X`A zZ`mlOr3s+^(^A=Rn!u>S{-Bjx;q39&o44wi*+LfVmyah;g%Q0fpx-j^k<;H3WdUKK z(LC=w@89AG0`{dfQ=r>;LdyaF{%WSubLaiJ-N#k`4Bw zHE2pQ-^w$|Fi zCpDc#Y)ef6-ErkM=LEA6v7pzvhICl|;x(OdY60Z~Pg=SV$wCf(7Go=Nw-?7b@OoyD>ZlphB#@X7?(+kXth?g(^@k2EPDW~Ay!7r z>=jA8o32Fhv0StEGyjKLmiXL#z}r(7zprkH$MsDjA;afRO#_zpgucT4_CmlY1DTr` zN+x5Bvz1GP>HHh?WAPJA#{EX%rc36$;|HSRHa&_t3E9W18w-lwB!NMOzH=V6ie3wu z(E8mV1<mMCWlEc9=B1%IM?72KzSsYH)-hFrA2*n>WqRJYQCXsg#(OEwfn1V zHTt!JZOh$b)thtyOlksBdTkCE<84D}u#xqAVnVccx1^-+eo5gi6h$98$$7*KR12@J`S#CM7d zF(BHi@70}~_$QC)I%ix_^nHryH{;zD0F#lm5%?XT{zu_OmE%I^sD}?i`Ul6=)Ln~5lt9D+ z_BMUFBQ^1Kr^v)GmjFQBh(97>IU}`&VZVH-qQ(GNm^4<9Kx)6*3}L+{d?SV>!43tD zER#U;dQAWwzTF2PZUbpBL{!Wq>Z=bJUsb^}AIaT*qvOE|4G1`;W4i^uPd_-Lz z@r3J7{>?!9xS0hyBkDS+2n-mYL4F+2XwA!|7=^=scazg!{nYxD?E{Ew^RQ|X)C^nW z0YiMzgmW+vdd0!5cmJ^6!!^gIsq0?j(5RvY2x~@2AQ7Hn`kV4Ez>uI1piKpyJqOGw zaiD3g9r#n{pjU%0uw(+I{_cC)pl3)45YmI-U-c(DI1B9&(r75(77eo~0+?uz9D8wN zW?LrgW4ycrd)h>+8Ef$yVuK;S(H<~?CNU>Do1>kty*?UXh_>2F5kM+t;v$^TV`sg; zDnG4L_5)}HWH6v}%t`m{3MDZ07^B|z|6udBVo7qgWYJr8h*6QoF$Z$Y zDHvxTZWR|pPJgvJSO1@Rv~dD@xe!+)nl}fxp{A_7r7uJ~s{?nrAn3JU zLKJWiVcbwZXq-zDqheNx=JfEEanFB`nRIi*@bR>BtP~7U_5$%m7<>vQH2FftT#Aw2 zXI8|FnN1yZGds+StYX~Imv!H1yq)>?`v_t{!(vogt>luJu4Q25Xj`M{OJDNsTgb7C zirZd!qfPj;75Sp7(vs-a-FUA0c6;(hBtQTq-^Wm0Zs^@WwLPSfjB#Q~l5s#!@^{pr z&IQt{XG@jkg}rl70;qNbuzb{;--btPYsK!Wp?V=Z@=q(9Z{+oXs8^Ys6%pt@>t75& z);1eXfsFgpdpE?U=L6OA^wy6V^yR^jSufBs?c!JCmXKO(>|L`YSR&~42H|c|@9#bL z?}YTrvB?{?MrgWc3zU`qax_vfuNW0Ow|_Eo+$exmdYy^D?@q^*!{u)4#}1bn320sK zUCjnR_FGw&;7X-(JDuVhb$JAcPb#DBlEkP>dLW3bu8g3kivGJ;iw?lu;bbrN$twMM ziK=IkEF9qvT2j&-Ska#<#%+7$n)We868M`L)-10ChRA&Y0YjEv>&GURw#09BDJnHp zAF%5R0-CM(z*aXc&Y=ar+yxE3`a*G;GVapvqSWbw8XABnY6V$7M%gY0ml27 zM|0jBWf`r1d2>72)8C0u0R~61<*boaM|0DhHJw)IjPg3I?IUj{p|?Du=*-Ah{f2u@ zpDDL90`ZS{W(FJDXk}LGg6K>dToI~?;(cE~fsRUE>Cxj#pB@PmHCOG_LW{*?H!S!1 zB%p*)xP)}gOS^N2Yu@FmY0@!EHsb`)>%Yq_USz7q>JF-5IzHl?54^9=A2fC+&P=$W z^I5YA0R45T=a}MjS(@u~XSG9RWUGs?(Lv`N0d5EuS0wx%`3yvO3vdu|qa<$P~bamB@#m$NESG=Qh(jnAeAenYg41HHp%+)Fx! zzmnPWJ6=SX*)n*Z-ck5Itgfz2enUpL(b?$LBo+DvBfg0wyx8%fu*L|pTwO*?z0-bL zGR^p1mW^WL7trf^3CtXhL`7CUCK2lXzCPUnK{@zS;Ac%K!*SZpW4RRLJfxpcPno^>Omk2PWAB%Dr>|C= zji$dM`hQPy`kx{H1pM9PcS1F+w^H1pxbG9+3?KJcRYMw`%AbH~kaxG+6)-{QeTGfhVTwWS0B2pZS4L(9D5Ja{#Nv)#+e}4HGz)l zJ>Cp16gyB3p&*eM=gsn0d|8s*MZy@Y~5qK!`Aa(xeQ9P=`}}n#=j_~`OwM!Fk5SDZ!&v$0 zOs~nR1433wQ3lszNc~l|5-yVm`g3xU^O$#SI496yT%5Qc9+E`E1mdW$$2buF?Dss9O{nwp3~jjU;*WiXL^?B ziv?q+D){d5{^QI_x%9+q85WkzeLYE1x|B3xo^@En2-*&Xko*ELSaAKJ0fd z8jO;NMjr9l>F#S4_Z`qGp}rB{%pAh2bO-orN5R!}hEv%frI@oIfcr$STqh1Wx1+YS$ zx)&`pOP@tG=u!u1Wo(GXQaYp_3xujyjf4=LX5&j6L>`EUuij9x)X$hniZBC<_*@f7 zfvU;|3$z0fHb@746}^TE&5YKbm(JBUg;ldl_z%5?7gA|c8XD?@GRZNr*rRnX1iq?TMHSOmlhG3l^NHTT&0eWdeMcCvg+neLsUbX3QtHY&Ao6!j zJz#@jN!R8>Fq}4=}J&dTA4hIcnc1>^hRluCUao z{RPz+H1+d0H!JSYq7xt)dK+Q60zN*Mf_M@5cYb!c9QKsnR)D)AWx?znA>hqfHg8K+ z*vw7UopQ^2$k{t_E)yk`>a?(=cZKKqtc&hhkbzg}4Z7+o!@t`-RL?pFl2}`686%n~ z7*z?8*aASoI}TY3Y0;9II(t4Xs-9o@jrl!5uOm=3zQe6bn0|HPb>8bL7lGQ%-DD!L z_;6i8&#ilzdg2}TpsAmeNKfbE86I>B1JhjiyuWLusK+NAKky9#B0Fh=?aN9{0k;#? zN*QYPj=)dzr}-GojD4^c{?Z|%yH-V&y1|4BIsXanuJ==dv1jB%SU%*taYinQaWlp; zGZLIwSx->mvwny%8;^c+ypHJW*^9C=_Eht;I zUM~7QQM1U+2Qzzfk%(uCGel!CjsS|6(Gd=dMVZ&B{n9=dqac8~n+$fsV(-M~c}@HE z09Z{M>j!go8pTJ5F$&EiiEr;1|MQuQx^}kMV{#yrHMz0`U(xk*#FHj+aWRkp-wI}3R8>sQ zEf#Pa?ejpnv_pl~Ue1Sr@fQoa_6}wzO<06xHQsUm3bX*?%beQtCY*c8hpNk^z|r5$ zk6th;&1dLYRegj+${mveWEc!IE&3YYr1l@%==F~y9hvrjjEt6jpzjU~>j4ENcXY@c zH*glG9|j-xv!Z-osP=aDbQhR4DF|{{Doa295Y(Ah<3MS9mioAbrqrM!{NxP(t3mSN7#>v@J!2^=0= zM_g2Xe2{lIu6%p(<%^+GodP#ee!Xf%%Ak?yMo^EdiNW5Pg=~p!wozdG1^^waD~5{@ zuVI_=2=3J6z_B1UT2SX+CFd2!v^V|sfa<1_X`%U@#cjfHeb*jV&N{WP3bDrvVi_as7fagmY2ohP;Fjm&#v9ZA z!L=$n(4T%5=u>Q1AFVp7pw*tc(mO3FrCUqYHr*%^gkGf!13;$D*t2FW?qYae!WB;o z9)3#`Y2m)vV^jibe~pQ9V=IMnqLFU~>lAPG(5gd+{^njSZ{=mcTtM9UlG_f-^w_AX zm93caFk?1gw`MQ?nrNiw)BHB@_SMYPHD?~1w=abC*=Wp=v!cE8J3l^{G{J^)n!NoG z08kEci-wOEfdHD<=BW`Z6NW1GvIb^gH~wbFpSc%H`$SHB73ApD4kKrCJj<{Io?3W{aK*$CAOaD7SU>~B6GOrF~XGa$=j~(*i;v+vR*4G1)MLF z%bFH_BoH=QxS?YwGR2|t6ruil$XNgK)2SVz~=wA=dL;A^YAsg-!8&JjDao{&~%(z2weaG z$^SbGK>1(xfAltG_IHVgC7l0h7Ya{Qv*} literal 0 HcmV?d00001 diff --git a/src/gui/plugins/tape_measure/tape_measure.svg b/src/gui/plugins/tape_measure/tape_measure.svg deleted file mode 100644 index 20b65f8e7c..0000000000 --- a/src/gui/plugins/tape_measure/tape_measure.svg +++ /dev/null @@ -1,82 +0,0 @@ - - - -image/svg+xml - - - - - - \ No newline at end of file From 2a84ddd753286c345445e1f64b35582c8efb928a Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Wed, 11 Nov 2020 15:51:55 -0800 Subject: [PATCH 11/21] disable right menu when measuring Signed-off-by: John Shepherd --- include/ignition/gazebo/gui/GuiEvents.hh | 45 ++++++++++++++++++ src/gui/plugins/scene3d/Scene3D.cc | 46 +++++++++++++++++++ src/gui/plugins/scene3d/Scene3D.hh | 7 +++ src/gui/plugins/tape_measure/TapeMeasure.cc | 29 ++++++++++++ .../transform_control/TransformControl.qml | 9 ++-- 5 files changed, 132 insertions(+), 4 deletions(-) diff --git a/include/ignition/gazebo/gui/GuiEvents.hh b/include/ignition/gazebo/gui/GuiEvents.hh index 3f3389e8a8..65fd3da315 100644 --- a/include/ignition/gazebo/gui/GuiEvents.hh +++ b/include/ignition/gazebo/gui/GuiEvents.hh @@ -262,6 +262,51 @@ namespace events /// \brief The 3D point that the user clicked within the scene. private: math::Vector3d point; }; + + /// \brief Event which is called to broadcast the 3D coordinates of a user's + /// right click within the scene. + class RightClickToScene : public QEvent + { + /// \brief Constructor + /// \param[in] _point The point which the user has right clicked within the + /// scene + public: explicit RightClickToScene(const math::Vector3d &_point) + : QEvent(kType), point(_point) + { + } + + /// \brief Unique type for this event. + static const QEvent::Type kType = QEvent::Type(QEvent::User + 8); + + /// \brief Get the point within the scene that the user clicked. + /// \return The 3D point. + public: math::Vector3d Point() const + { + return this->point; + } + + /// \brief The 3D point that the user clicked within the scene. + private: math::Vector3d point; + }; + + class RightClickDropdownMenu : public QEvent + { + /// \brief Constructor + public: explicit RightClickDropdownMenu(bool _menuEnabled) + : QEvent(kType), menuEnabled(_menuEnabled) + { + } + + /// \brief Unique type for this event. + static const QEvent::Type kType = QEvent::Type(QEvent::User + 9); + + public: bool MenuEnabled() const + { + return this->menuEnabled; + } + + private: bool menuEnabled; + }; } // namespace events } } // namespace gui diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 5840b0d84b..cb13460ed7 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -236,6 +236,8 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// resource with the shapes plugin or not public: bool isPlacing = false; + public: std::atomic_bool rightClickMenuEnabled = true; + /// \brief The SDF string of the resource to be used with plugins that spawn /// entities. public: std::string spawnSdfString; @@ -769,6 +771,7 @@ void IgnRenderer::HandleMouseEvent() std::lock_guard lock(this->dataPtr->mutex); this->BroadcastHoverPos(); this->BroadcastLeftClick(); + this->BroadcastRightClick(); this->HandleMouseContextMenu(); this->HandleModelPlacement(); this->HandleMouseTransformControl(); @@ -805,6 +808,26 @@ void IgnRenderer::BroadcastLeftClick() } } +///////////////////////////////////////////////// +void IgnRenderer::BroadcastRightClick() +{ + if (this->dataPtr->mouseEvent.Button() == common::MouseEvent::RIGHT && + this->dataPtr->mouseEvent.Type() == common::MouseEvent::RELEASE && + !this->dataPtr->mouseEvent.Dragging() && this->dataPtr->mouseDirty) + { + // If the right click menu is disabled, quash the mouse event + if (!this->dataPtr->rightClickMenuEnabled) + this->dataPtr->mouseDirty = false; + + math::Vector3d pos = this->ScreenToScene(this->dataPtr->mouseEvent.Pos()); + + gui::events::RightClickToScene rightClickToSceneEvent(pos); + ignition::gui::App()->sendEvent( + ignition::gui::App()->findChild(), + &rightClickToSceneEvent); + } +} + ///////////////////////////////////////////////// void IgnRenderer::HandleMouseContextMenu() { @@ -1687,6 +1710,12 @@ void IgnRenderer::SetModelPath(const std::string &_filePath) this->dataPtr->spawnSdfPath = _filePath; } +///////////////////////////////////////////////// +void IgnRenderer::SetRightClickMenu(bool _enableRightClickMenu) +{ + this->dataPtr->rightClickMenuEnabled = _enableRightClickMenu; +} + ///////////////////////////////////////////////// void IgnRenderer::SetRecordVideo(bool _record, const std::string &_format, const std::string &_savePath) @@ -2658,6 +2687,17 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) renderWindow->SetModelPath(spawnPreviewPathEvent->FilePath()); } } + else if (_event->type() == + ignition::gazebo::gui::events::RightClickDropdownMenu::kType) + { + auto rightClickDropdownMenuEvent = + reinterpret_cast(_event); + if (rightClickDropdownMenuEvent) + { + auto renderWindow = this->PluginItem()->findChild(); + renderWindow->SetRightClickMenu(rightClickDropdownMenuEvent->MenuEnabled()); + } + } // Standard event processing return QObject::eventFilter(_obj, _event); @@ -2689,6 +2729,12 @@ void RenderWindowItem::SetModelPath(const std::string &_filePath) this->dataPtr->renderThread->ignRenderer.SetModelPath(_filePath); } +///////////////////////////////////////////////// +void RenderWindowItem::SetRightClickMenu(bool _enableRightClickMenu) +{ + this->dataPtr->renderThread->ignRenderer.SetRightClickMenu(_enableRightClickMenu); +} + ///////////////////////////////////////////////// void RenderWindowItem::SetRecordVideo(bool _record, const std::string &_format, const std::string &_savePath) diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index c8d1e192e9..d9bc12ea52 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -199,6 +199,8 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \param[in] _filePath Sdf path of the model to load in for the user. public: void SetModelPath(const std::string &_filePath); + public: void SetRightClickMenu(bool _enableRightClickMenu); + /// \brief Set whether to record video /// \param[in] _record True to start video recording, false to stop. /// \param[in] _format Video encoding format: "mp4", "ogv" @@ -357,6 +359,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Broadcasts a left click within the scene private: void BroadcastLeftClick(); + /// \brief Broadcasts a right click within the scene + private: void BroadcastRightClick(); + /// \brief Generate a unique entity id. /// \return The unique entity id private: Entity UniqueId(); @@ -514,6 +519,8 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \param[in] _filePath File path of the model to load in for the user. public: void SetModelPath(const std::string &_filePath); + public: void SetRightClickMenu(bool _enableRightClickMenu); + /// \brief Set whether to record video /// \param[in] _record True to start video recording, false to stop. /// \param[in] _format Video encoding format: "mp4", "ogv" diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index ee6e431eb7..91cc1136ac 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -113,6 +113,13 @@ void TapeMeasure::OnMeasure() this->Reset(); this->dataPtr->measure = true; QGuiApplication::setOverrideCursor(Qt::CrossCursor); + + // Notify Scene3D to disable the right click menu while we use it to + // cancel our current measuring action + gui::events::RightClickDropdownMenu rightClickDropdownMenuEvent(false); + ignition::gui::App()->sendEvent( + ignition::gui::App()->findChild(), + &rightClickDropdownMenuEvent); } ///////////////////////////////////////////////// @@ -136,6 +143,13 @@ void TapeMeasure::Reset() this->dataPtr->measure = false; this->newDistance(); QGuiApplication::restoreOverrideCursor(); + + // Notify Scene3D that we are done using the right click, so it can + // re-enable the settings menu + gui::events::RightClickDropdownMenu rightClickDropdownMenuEvent(true); + ignition::gui::App()->sendEvent( + ignition::gui::App()->findChild(), + &rightClickDropdownMenuEvent); } ///////////////////////////////////////////////// @@ -269,10 +283,25 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) this->dataPtr->startPoint.Distance(this->dataPtr->endPoint); this->newDistance(); QGuiApplication::restoreOverrideCursor(); + + // Notify Scene3D that we are done using the right click, so it can + // re-enable the settings menu + gui::events::RightClickDropdownMenu rightClickDropdownMenuEvent(true); + ignition::gui::App()->sendEvent( + ignition::gui::App()->findChild(), + &rightClickDropdownMenuEvent); } this->dataPtr->currentId = this->dataPtr->endPointId; } } + // Cancel the current action if a right click is detected + else if (_event->type() == ignition::gazebo::gui::events::RightClickToScene::kType) + { + if (this->dataPtr->measure) + { + this->Reset(); + } + } return QObject::eventFilter(_obj, _event); } diff --git a/src/gui/plugins/transform_control/TransformControl.qml b/src/gui/plugins/transform_control/TransformControl.qml index 765506c45b..751a8054ea 100644 --- a/src/gui/plugins/transform_control/TransformControl.qml +++ b/src/gui/plugins/transform_control/TransformControl.qml @@ -55,6 +55,7 @@ ToolBar { function activateSelect() { select.checked = true; TransformControl.OnMode("select"); + print("pressed escape transform"); } function updateSnapValues() { @@ -107,10 +108,10 @@ ToolBar { onActivated: activateRotate() } - Shortcut { - sequence: "Esc" - onActivated: activateSelect() - } + //Shortcut { + // sequence: "Esc" + // onActivated: activateSelect() + //} RowLayout { spacing: 2 From b07c5d93ceb816d710b818174da89745ef71258d Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Wed, 11 Nov 2020 16:06:33 -0800 Subject: [PATCH 12/21] Add docs Signed-off-by: John Shepherd --- include/ignition/gazebo/gui/GuiEvents.hh | 15 ++++++++++++--- src/gui/plugins/scene3d/Scene3D.cc | 2 ++ src/gui/plugins/scene3d/Scene3D.hh | 6 ++++++ .../transform_control/TransformControl.qml | 9 ++++----- 4 files changed, 24 insertions(+), 8 deletions(-) diff --git a/include/ignition/gazebo/gui/GuiEvents.hh b/include/ignition/gazebo/gui/GuiEvents.hh index 65fd3da315..0f7765839d 100644 --- a/include/ignition/gazebo/gui/GuiEvents.hh +++ b/include/ignition/gazebo/gui/GuiEvents.hh @@ -289,22 +289,31 @@ namespace events private: math::Vector3d point; }; + /// \brief Event which is called to enable or disable the right click dropdown + /// menu. This is primarily used by plugins which also use the right click to + /// cancel any actions currently in progress. class RightClickDropdownMenu : public QEvent { /// \brief Constructor + /// \param[in] _menuEnabled The boolean indicating whether the dropdown + /// menu should be enabled or disabled. public: explicit RightClickDropdownMenu(bool _menuEnabled) : QEvent(kType), menuEnabled(_menuEnabled) { } - + /// \brief Unique type for this event. static const QEvent::Type kType = QEvent::Type(QEvent::User + 9); + /// \brief Gets whether the menu is enabled or not for this event. + /// \return True if enabling the menu, false if disabling the menu public: bool MenuEnabled() const - { + { return this->menuEnabled; } - + + /// \brief The boolean indicating whether the menu is disabled or not + /// for this event. private: bool menuEnabled; }; } // namespace events diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index cb13460ed7..94536b4228 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -236,6 +236,8 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// resource with the shapes plugin or not public: bool isPlacing = false; + /// \brief Atomic bool indicating whether the right click menu + /// is currently enabled or disabled. public: std::atomic_bool rightClickMenuEnabled = true; /// \brief The SDF string of the resource to be used with plugins that spawn diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index d9bc12ea52..5dcbcc59e9 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -199,6 +199,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \param[in] _filePath Sdf path of the model to load in for the user. public: void SetModelPath(const std::string &_filePath); + /// \brief Set if the right click menu is enabled or disabled. + /// \param[in] _enableRightClickMenu The boolean to enable or disable + /// the menu public: void SetRightClickMenu(bool _enableRightClickMenu); /// \brief Set whether to record video @@ -519,6 +522,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \param[in] _filePath File path of the model to load in for the user. public: void SetModelPath(const std::string &_filePath); + /// \brief Set if the right click menu is enabled or disabled. + /// \param[in] _enableRightClickMenu The boolean to enable or disable + /// the menu public: void SetRightClickMenu(bool _enableRightClickMenu); /// \brief Set whether to record video diff --git a/src/gui/plugins/transform_control/TransformControl.qml b/src/gui/plugins/transform_control/TransformControl.qml index 751a8054ea..765506c45b 100644 --- a/src/gui/plugins/transform_control/TransformControl.qml +++ b/src/gui/plugins/transform_control/TransformControl.qml @@ -55,7 +55,6 @@ ToolBar { function activateSelect() { select.checked = true; TransformControl.OnMode("select"); - print("pressed escape transform"); } function updateSnapValues() { @@ -108,10 +107,10 @@ ToolBar { onActivated: activateRotate() } - //Shortcut { - // sequence: "Esc" - // onActivated: activateSelect() - //} + Shortcut { + sequence: "Esc" + onActivated: activateSelect() + } RowLayout { spacing: 2 From 83b0a4399a911fc305ac40f7fd533d38fb4d9a0f Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Wed, 11 Nov 2020 23:21:58 -0800 Subject: [PATCH 13/21] Updates Signed-off-by: John Shepherd --- src/gui/plugins/tape_measure/TapeMeasure.cc | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index ee6e431eb7..da8b3ac100 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -131,7 +131,6 @@ void TapeMeasure::Reset() this->dataPtr->currentId = this->dataPtr->startPointId; this->dataPtr->startPoint = ignition::math::Vector3d::Zero; this->dataPtr->endPoint = ignition::math::Vector3d::Zero; - this->dataPtr->placedMarkers.clear(); this->dataPtr->distance = 0.0; this->dataPtr->measure = false; this->newDistance(); @@ -157,6 +156,7 @@ void TapeMeasure::DeleteMarker(int _id) markerMsg.set_id(_id); markerMsg.set_action(ignition::msgs::Marker::DELETE_MARKER); this->dataPtr->node.Request("/marker", markerMsg); + this->dataPtr->placedMarkers.erase(_id); } ///////////////////////////////////////////////// @@ -164,7 +164,6 @@ void TapeMeasure::DrawPoint(int _id, ignition::math::Vector3d &_point, ignition::math::Vector4d &_color) { this->DeleteMarker(_id); - this->dataPtr->placedMarkers.insert(_id); ignition::msgs::Marker markerMsg; markerMsg.set_ns(this->dataPtr->ns); @@ -185,6 +184,7 @@ void TapeMeasure::DrawPoint(int _id, ignition::math::Pose3d(_point.X(), _point.Y(), _point.Z(), 0, 0, 0)); this->dataPtr->node.Request("/marker", markerMsg); + this->dataPtr->placedMarkers.insert(_id); } ///////////////////////////////////////////////// @@ -192,7 +192,6 @@ void TapeMeasure::DrawLine(int _id, ignition::math::Vector3d &_startPoint, ignition::math::Vector3d &_endPoint, ignition::math::Vector4d &_color) { this->DeleteMarker(_id); - this->dataPtr->placedMarkers.insert(_id); ignition::msgs::Marker markerMsg; markerMsg.set_ns(this->dataPtr->ns); @@ -211,6 +210,7 @@ void TapeMeasure::DrawLine(int _id, ignition::math::Vector3d &_startPoint, ignition::msgs::Set(markerMsg.add_point(), _endPoint); this->dataPtr->node.Request("/marker", markerMsg); + this->dataPtr->placedMarkers.insert(_id); } ///////////////////////////////////////////////// From e69d95a2fb05903dc124b7a84d243e76ac5097c8 Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Fri, 13 Nov 2020 10:36:58 -0800 Subject: [PATCH 14/21] Add in trashcan icon Signed-off-by: John Shepherd --- src/gui/plugins/tape_measure/TapeMeasure.qml | 6 +++--- src/gui/plugins/tape_measure/trashcan.png | Bin 1256 -> 5374 bytes 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/gui/plugins/tape_measure/TapeMeasure.qml b/src/gui/plugins/tape_measure/TapeMeasure.qml index c9dd482b42..1c9135cbcf 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.qml +++ b/src/gui/plugins/tape_measure/TapeMeasure.qml @@ -68,7 +68,7 @@ ToolBar { } RowLayout { - spacing: 2 + spacing: 1 ToolButton { id: select checkable: true @@ -102,8 +102,8 @@ ToolBar { horizontalAlignment: Image.AlignHCenter verticalAlignment: Image.AlignVCenter source: "trashcan.png" - sourceSize.width: 24; - sourceSize.height: 24; + sourceSize.width: 36; + sourceSize.height: 36; } onClicked: { TapeMeasure.OnReset(); diff --git a/src/gui/plugins/tape_measure/trashcan.png b/src/gui/plugins/tape_measure/trashcan.png index 6ea9ed48a5cb727a2645b293fdb821c59f71039e..62edd38a51941951e7b9316181314cd45350480b 100644 GIT binary patch literal 5374 zcmb_gi9gic_rISpV=Gw)A?A5XvV}+_Om-?fNS0)M6hcE;qD)dmmWq^wo(c&w$etxJ zBWt!~UxtJ%W8eMm^!&cB-yiV%&g(TZ_kQkj&OPUS-sjxU15;yt4t61S004)ffsPpf zDA+^+Ry6#(L=YhWz*lFebJ`-HcV-|c`^~srHGPQOn7=x1#?SvN6fe2@!SqPqQ_575 zlTMONr;!n_c7lOYoRUTKJG^^VdSQH#l2-O#Q3}xshs{uJrVZ@*>75*j`DUdBedGD7 zo8!p`cE1+{wfuTMaO+3Y$Hc(Y*6^_Qfz_s__2#D4Q;HL}hTQCg@wqX_P+R~H00Pk9 zzt#Bf?ewokSDsN{+kMhJA+$B`Vdug8d1fKtpZw`Te%}Ga5?D+=U?&9`U-e;O1zkOM z^ySvr>3+6LDANSL1ESiq%+m05N4m@o;=#g=Qf?erPr4PMIV2dupL1uY;E<^N?BOIY zG)Dm~&iW^Hp+xFWuNbwx-`R;9y*Bk7AyuTCRC|zF5O~l2bKQLz(Al9bev!)V%nzm} z@0;b0OEAlVv1$8gJgD#He8~8Ht%n1|-+l%-P#t$o-n8;*?IgkGYJ>nSgPufS1)pb& zX&OVGv zMRs(pts}EBH8%Ml1V*(^^^Q~Ik9Q8pv7+l;h7TY+QO$q6wWCa`+ zjgl+-jKO)Ip(T~bv`CGx?ws_XP6bGbMpZ2lxrphSBbwZa6zja|Bm0EI&ePAzL{%MQ zM+CjZVoWHTqgPGVDt|?H(JfB#*ekFjndKzv-*hjNwa~j{sgxKoioNhXU@_AY5R!a= zx?ks>p7Z%rSj`BvXe|)ALZ#=aNW>hE=w%u4rrmzcMSNHO$5Vb%~z&n{+Us#v_Tis%4oG-|YlBV&P1W>YL6X*e3kHFZgfoJz-p2o~&9bcLA zs|^b&rtJI}&N;a|u)dsgl-J{2NthpXH%dj-RcY+eqk$26hx&GSEhRub<>C0-;5B_s zuh=uRP!;iX4qEKzfI}Kin6EA-6me~WS}|3cab)j(+qH?cR42pa{ZaSFGCa-lTd3dO@{0DsR{kI&LXFxYb}i&$!sZd5 z-qm#-laP~JHo?YVq0Mt{X&?n-z4;i7&D?B7&^Y_mo2)Lga~QC&tcHpsC7#;hCSE){ z$njHw6QFSdPeMjkV?{yjC8YiaW}d9CnRf~J*dh2@OU47h-G{DbCkD^(0BNw0uuS_i z<2BM@38oJRTj&*&u8OUdL~n~#wXGu}GfW{Tce)0O=59~-+U>l-z7%U#pesMLZ?D~r zWU_CYU3e)rb#mX%3+;h#-%clrJ}L6JvA+4mT%?NPHT31xPUUe&6sepqOK=xi=4tx?Vy1HUoocLB$Q~(t>at560!BoHGL^)uD9C8{b@#H*$~|H&Eg&w zhg5?l_Qu(JK(^W_pt9coE)BVA zyT=o)ef2FjD?Y?;KLTNg1N(d3(5(1MKf(WWofut+090IF4pYg)Xu3e#$tKOj+M(L1 znyM$^qyC&h(kr{Z`djuR#p7)y>*V5*skPkjOZ$_#e;QPZhJ2-7&=iGMg9Ex%S%hKYg!^$*&t_r>PWS21&jQ0s`^B2+P>2pe!*p}XV&T>zVrC9 zT(cF8)rl-3#@V%Pr`${e=e4z+-Oj?PZsgFX8~oRASe5emo>YZ^)xp^!^Q%KZ*e> z-f&iGZDD%pJ?U?4UlJ=3#E%K z;I|^Y)Ps+~W?D2~T4v6P~oo8y5r$UH1wWuC;^x?K~kmyF-` z=y@MpsSwDC2T5*0HOd7K-9n#267qfX%fcNqtPYTR6;KfU zh8PVMp!o0$J7aN0B7mn9X=$U3i4%cR$9uNEvnSHof{&4al0m~e@n0LEK&jK{AmbFU z%7u%G+KVv}zyV|WM^!i%IHv4`M&ZwA4PgUf)lS0-&iEh~Sh$5b3Q%~8pYR=EnlLpK z+Bag%1+vJR^>)A6rMLq6kp?xoaxp`3{ zFuh#2BQ$RXfk6zu03;-?E*3#K%+ybBZ}@1{D0@JMGE-B=DV7ha_ekXK{3+fc!o&}d%mSy7J@VZ|Oxnd5+4mjn4n@cwd}-1C)6tdynpwQh1%2EG zX;O569>dvF1@D0P#!2y;ic*Zxbtykh;&WyhFy5O?Zgz5(k_3u-tw2M9&$UTOiiH_S z7bZiOS0c|`t5K%8g=~GvSI)BH6)PT-o3)%zI*_1qo@5(;r-)9`^k4=_8Y>L*{2|;Z!-0k$xGq8v2F4W5{`{`!pmj2a z$bP;;dfwIl4g=fOETybqKM8z9bN!B$6OO_e1OXuAeg`UI>aCl?gJvUm9&h-xF% z^{JcAJj74=zHWAwKr+MLe*7pG17Y#LayzjKY(!v@QEzugK#;^hKQ>T4PEn2xkMR>c z%^BIxSR%GArNrhpHy%uaO7r7-%^p#`BV~T`M zbN0fcTtZnPe4i$};VF(?Lf{@2xbZ{g6GG-}(!|%%7eGVtAC52XQIuS3oh?C<`1o3W z9YraWBm}8{7>riG_<_Zw-M$OVXr%|Sl z4xmh#eBpH~E6*CZR|i3U;SPV+`AG&s(cK~_<$1*{fNsGJ0dj0dE*oA~Ie;^bIr*j? zkQ&u7hrtr3P=(24lDLE=MrNP;{=>%^GAGg124AY5j8%nu;-Rs{X`wg_XTHk=cz`nNbNt4574IAS2S29*xt0U2(`1ufa2n!43* zuuo*j*@DqFjluT~j=CB%fYvn(5wV?T~E_7IuTM?WQCsBooFbLwkb{7T!7Ej1J zHSwuG%u_jt%nIt>Eeu4&`yTc35nv-`*eSjZUh36@i8@L0Zw$GGA(!-dbzj#L@)1c1 zJG<#SQlKt#ftb9p#h=z-`0@mS&%>RO}%_DUJ# zl^bR;ing6=s~~GE8`^ylTdn1+1!at@6wuhqW;c?j+Ks=U;@-``JRtY8Y`WlJoZVwI z&RmiusYUu{Sp^Fb>^%+m`K}Kvub0Ad9=N!h-$OE6J7%wNqLF&@hDSeiU&>`@$RP}j zo7?gfNxGX<7q~0l>k(x|#bv~spZoYeZCc}OClRXVDBgS5f`-)U=6<|YDQNZB zNi0cUDz!!AzvN4vx-~aV+YtTbj3u0Ff7STTD|#h9)#9>_TFVTr%ztHTNguG!`*osfwT-6o;>)d9Dz?@xTU%Kn+28hy!BlB-Vt zfj_DbJ}z9g5*yO{eX)U6Nh~7(&;VhCg-?DTD@>%GCr~gG0|cjC4tZc6=4G6=8f2mR z?tP5(UD)+|(lONUHOH2cAyz6S8G#si+EhZ>f`Ld%T@)4F;~? zj>PLo$4r%ZPROdPZK`j59E}L^eXU=U1TF+{(JaZG%Q-e|yQz{EjrrIztu#|ebIEGZ*dUO3CZyP{rqesevdE6?vOb1TFv z^2~*On>iU;1RW$8i6R&hSp?iLi46bk>s}|dIZJ$sIa`o%-bUYe%lh-ivlz=B9)G6A ztI)%6hyzY!Fk$M)W+qsSSa$){VK<}U*q2H*V}_cNtzp^>JG_`Vlp73~h#t4#AVg Date: Thu, 19 Nov 2020 17:46:54 -0800 Subject: [PATCH 15/21] add in gui events Signed-off-by: John Shepherd --- src/gui/plugins/scene3d/Scene3D.cc | 5 +++-- src/gui/plugins/tape_measure/TapeMeasure.cc | 5 +++-- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 5840b0d84b..1844dd1fd5 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -55,6 +55,7 @@ #include #include +#include #include #include @@ -782,7 +783,7 @@ void IgnRenderer::BroadcastHoverPos() { math::Vector3d pos = this->ScreenToScene(this->dataPtr->mouseHoverPos); - gui::events::HoverToScene hoverToSceneEvent(pos); + ignition::gui::events::HoverToScene hoverToSceneEvent(pos); ignition::gui::App()->sendEvent( ignition::gui::App()->findChild(), &hoverToSceneEvent); @@ -798,7 +799,7 @@ void IgnRenderer::BroadcastLeftClick() { math::Vector3d pos = this->ScreenToScene(this->dataPtr->mouseEvent.Pos()); - gui::events::LeftClickToScene leftClickToSceneEvent(pos); + ignition::gui::events::LeftClickToScene leftClickToSceneEvent(pos); ignition::gui::App()->sendEvent( ignition::gui::App()->findChild(), &leftClickToSceneEvent); diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index da8b3ac100..01a6e473fa 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -19,6 +19,7 @@ #include #include #include +#include #include #include #include @@ -216,7 +217,7 @@ void TapeMeasure::DrawLine(int _id, ignition::math::Vector3d &_startPoint, ///////////////////////////////////////////////// bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) { - if (_event->type() == ignition::gazebo::gui::events::HoverToScene::kType) + if (_event->type() == ignition::gui::events::HoverToScene::kType) { auto hoverToSceneEvent = reinterpret_cast(_event); @@ -240,7 +241,7 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) } } } - else if (_event->type() == ignition::gazebo::gui::events::LeftClickToScene::kType) + else if (_event->type() == ignition::gui::events::LeftClickToScene::kType) { auto leftClickToSceneEvent = reinterpret_cast(_event); From a31264c805a30022a5db6388687fe25ef06079a6 Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Thu, 19 Nov 2020 17:47:32 -0800 Subject: [PATCH 16/21] Remove events from gazebo gui Signed-off-by: John Shepherd --- include/ignition/gazebo/gui/GuiEvents.hh | 52 ------------------------ 1 file changed, 52 deletions(-) diff --git a/include/ignition/gazebo/gui/GuiEvents.hh b/include/ignition/gazebo/gui/GuiEvents.hh index 3f3389e8a8..6af9c5a69c 100644 --- a/include/ignition/gazebo/gui/GuiEvents.hh +++ b/include/ignition/gazebo/gui/GuiEvents.hh @@ -210,58 +210,6 @@ namespace events /// \brief The path of SDF file to be previewed. std::string filePath; }; - - /// \brief Event which is called to broadcast the 3D coordinates of a user's - /// mouse hover within the scene. - class HoverToScene : public QEvent - { - /// \brief Constructor - /// \param[in] _point The point at which the mouse is hovering within the - /// scene - public: explicit HoverToScene(const math::Vector3d &_point) - : QEvent(kType), point(_point) - { - } - - /// \brief Unique type for this event. - static const QEvent::Type kType = QEvent::Type(QEvent::User + 6); - - /// \brief Get the point within the scene over which the user is hovering. - /// \return The 3D point - public: math::Vector3d Point() const - { - return this->point; - } - - /// \brief The 3D point over which the user is hovering. - private: math::Vector3d point; - }; - - /// \brief Event which is called to broadcast the 3D coordinates of a user's - /// left click within the scene. - class LeftClickToScene : public QEvent - { - /// \brief Constructor - /// \param[in] _point The point which the user has left clicked within the - /// scene - public: explicit LeftClickToScene(const math::Vector3d &_point) - : QEvent(kType), point(_point) - { - } - - /// \brief Unique type for this event. - static const QEvent::Type kType = QEvent::Type(QEvent::User + 7); - - /// \brief Get the point within the scene that the user clicked. - /// \return The 3D point. - public: math::Vector3d Point() const - { - return this->point; - } - - /// \brief The 3D point that the user clicked within the scene. - private: math::Vector3d point; - }; } // namespace events } } // namespace gui From dda9038aef5fc0e953aadaea329fca4f37d20695 Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Thu, 19 Nov 2020 23:54:45 -0800 Subject: [PATCH 17/21] requested fixes Signed-off-by: John Shepherd --- src/gui/plugins/tape_measure/TapeMeasure.cc | 49 ++++++++------------ src/gui/plugins/tape_measure/TapeMeasure.hh | 6 +-- src/gui/plugins/tape_measure/TapeMeasure.qml | 10 +--- 3 files changed, 24 insertions(+), 41 deletions(-) diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index 01a6e473fa..6a40cf7ffa 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -14,21 +14,26 @@ * limitations under the License. * */ -#include + +#include "ignition/gazebo/gui/GuiEvents.hh" + +#include "TapeMeasure.hh" #include +#include +#include +#include + #include #include #include #include +#include +#include #include #include #include -#include "ignition/gazebo/gui/GuiEvents.hh" - -#include "TapeMeasure.hh" - namespace ignition::gazebo { class TapeMeasurePrivate @@ -64,13 +69,11 @@ namespace ignition::gazebo /// \brief The color to set the marker when hovering the mouse over the /// scene. - public: ignition::math::Vector4d hoverColor = - ignition::math::Vector4d(0.2, 0.2, 0.2, 0.5); + public: ignition::math::Color hoverColor{ignition::math::Color(0.2, 0.2, 0.2, 0.5)}; /// \brief The color to draw the marker when the user clicks to confirm /// its location. - public: ignition::math::Vector4d drawColor = - ignition::math::Vector4d(0.2, 0.2, 0.2, 1.0); + public: ignition::math::Color drawColor{ignition::math::Color(0.2, 0.2, 0.2, 1.0)}; /// \brief A set of the currently placed markers. Used to make sure a /// non-existent marker is not deleted. @@ -162,7 +165,7 @@ void TapeMeasure::DeleteMarker(int _id) ///////////////////////////////////////////////// void TapeMeasure::DrawPoint(int _id, - ignition::math::Vector3d &_point, ignition::math::Vector4d &_color) + ignition::math::Vector3d &_point, ignition::math::Color &_color) { this->DeleteMarker(_id); @@ -171,16 +174,10 @@ void TapeMeasure::DrawPoint(int _id, markerMsg.set_id(_id); markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); markerMsg.set_type(ignition::msgs::Marker::SPHERE); + ignition::msgs::Set(markerMsg.mutable_material()->mutable_ambient(), _color); + ignition::msgs::Set(markerMsg.mutable_material()->mutable_diffuse(), _color); ignition::msgs::Set(markerMsg.mutable_scale(), ignition::math::Vector3d(0.1, 0.1, 0.1)); - markerMsg.mutable_material()->mutable_ambient()->set_r(_color[0]); - markerMsg.mutable_material()->mutable_ambient()->set_g(_color[1]); - markerMsg.mutable_material()->mutable_ambient()->set_b(_color[2]); - markerMsg.mutable_material()->mutable_ambient()->set_a(_color[3]); - markerMsg.mutable_material()->mutable_diffuse()->set_r(_color[0]); - markerMsg.mutable_material()->mutable_diffuse()->set_g(_color[1]); - markerMsg.mutable_material()->mutable_diffuse()->set_b(_color[2]); - markerMsg.mutable_material()->mutable_diffuse()->set_a(_color[3]); ignition::msgs::Set(markerMsg.mutable_pose(), ignition::math::Pose3d(_point.X(), _point.Y(), _point.Z(), 0, 0, 0)); @@ -190,7 +187,7 @@ void TapeMeasure::DrawPoint(int _id, ///////////////////////////////////////////////// void TapeMeasure::DrawLine(int _id, ignition::math::Vector3d &_startPoint, - ignition::math::Vector3d &_endPoint, ignition::math::Vector4d &_color) + ignition::math::Vector3d &_endPoint, ignition::math::Color &_color) { this->DeleteMarker(_id); @@ -199,14 +196,8 @@ void TapeMeasure::DrawLine(int _id, ignition::math::Vector3d &_startPoint, markerMsg.set_id(_id); markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY); markerMsg.set_type(ignition::msgs::Marker::LINE_LIST); - markerMsg.mutable_material()->mutable_ambient()->set_r(_color[0]); - markerMsg.mutable_material()->mutable_ambient()->set_g(_color[1]); - markerMsg.mutable_material()->mutable_ambient()->set_b(_color[2]); - markerMsg.mutable_material()->mutable_ambient()->set_a(_color[3]); - markerMsg.mutable_material()->mutable_diffuse()->set_r(_color[0]); - markerMsg.mutable_material()->mutable_diffuse()->set_g(_color[1]); - markerMsg.mutable_material()->mutable_diffuse()->set_b(_color[2]); - markerMsg.mutable_material()->mutable_diffuse()->set_a(_color[3]); + ignition::msgs::Set(markerMsg.mutable_material()->mutable_ambient(), _color); + ignition::msgs::Set(markerMsg.mutable_material()->mutable_diffuse(), _color); ignition::msgs::Set(markerMsg.add_point(), _startPoint); ignition::msgs::Set(markerMsg.add_point(), _endPoint); @@ -220,7 +211,7 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) if (_event->type() == ignition::gui::events::HoverToScene::kType) { auto hoverToSceneEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); // This event is called in Scene3d's RenderThread, so it's safe to make // rendering calls here @@ -244,7 +235,7 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) else if (_event->type() == ignition::gui::events::LeftClickToScene::kType) { auto leftClickToSceneEvent = - reinterpret_cast(_event); + reinterpret_cast(_event); // This event is called in Scene3d's RenderThread, so it's safe to make // rendering calls here diff --git a/src/gui/plugins/tape_measure/TapeMeasure.hh b/src/gui/plugins/tape_measure/TapeMeasure.hh index 9d7baca2b5..7d6417e30b 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.hh +++ b/src/gui/plugins/tape_measure/TapeMeasure.hh @@ -19,7 +19,7 @@ #include #include -#include +#include namespace ignition { @@ -58,7 +58,7 @@ namespace gazebo /// \param[in] _color The rgba color to set the marker public: void DrawPoint(int _id, ignition::math::Vector3d &_point, - ignition::math::Vector4d &_color); + ignition::math::Color &_color); /// \brief Draws a line marker. Called to display the line between the /// start and end point of the tape measure. @@ -69,7 +69,7 @@ namespace gazebo public: void DrawLine(int _id, ignition::math::Vector3d &_startPoint, ignition::math::Vector3d &_endPoint, - ignition::math::Vector4d &_color); + ignition::math::Color &_color); /// \brief Callback in Qt thread when the new measurement button is /// clicked. diff --git a/src/gui/plugins/tape_measure/TapeMeasure.qml b/src/gui/plugins/tape_measure/TapeMeasure.qml index 1c9135cbcf..7b9453d348 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.qml +++ b/src/gui/plugins/tape_measure/TapeMeasure.qml @@ -25,17 +25,9 @@ import "qrc:/qml" ToolBar { id: tapeMeasure - Layout.minimumWidth: 200 + Layout.minimumWidth: 250 Layout.minimumHeight: 100 - property color snapTitle: (Material.theme == Material.Light) ? - Material.color(Material.Grey, Material.Shade900) : - Material.color(Material.Grey, Material.Shade200) - - property color snapItem: (Material.theme == Material.Light) ? - Material.color(Material.Grey, Material.Shade800) : - Material.color(Material.Grey, Material.Shade100) - property var distance: 0.0 function updateDistance() { From 4d41ebe04525263d82069ea2d1d3f31c66711731 Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Fri, 20 Nov 2020 00:26:26 -0800 Subject: [PATCH 18/21] More fixes Signed-off-by: John Shepherd --- src/gui/plugins/tape_measure/TapeMeasure.cc | 32 +++++++++++--------- src/gui/plugins/tape_measure/TapeMeasure.hh | 2 ++ src/gui/plugins/tape_measure/TapeMeasure.qml | 2 ++ 3 files changed, 21 insertions(+), 15 deletions(-) diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index 6a40cf7ffa..79174f7529 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -45,18 +45,18 @@ namespace ignition::gazebo public: bool measure = false; /// \brief The id of the start point marker. - public: int startPointId = 1; + public: const int kStartPointId = 1; /// \brief The id of the end point marker. - public: int endPointId = 2; + public: const int kEndPointId = 2; /// \brief The id of the line marker. - public: int lineId = 3; + public: const int kLineId = 3; /// \brief The id of the start or end point marker that is currently /// being placed. This is primarily used to track the state machine of /// the plugin. - public: int currentId = startPointId; + public: int currentId = kStartPointId; /// \brief The location of the placed starting point of the tape measure /// tool, only set when the user clicks to set the point. @@ -69,11 +69,13 @@ namespace ignition::gazebo /// \brief The color to set the marker when hovering the mouse over the /// scene. - public: ignition::math::Color hoverColor{ignition::math::Color(0.2, 0.2, 0.2, 0.5)}; + public: ignition::math::Color + hoverColor{ignition::math::Color(0.2, 0.2, 0.2, 0.5)}; /// \brief The color to draw the marker when the user clicks to confirm /// its location. - public: ignition::math::Color drawColor{ignition::math::Color(0.2, 0.2, 0.2, 1.0)}; + public: ignition::math::Color + drawColor{ignition::math::Color(0.2, 0.2, 0.2, 1.0)}; /// \brief A set of the currently placed markers. Used to make sure a /// non-existent marker is not deleted. @@ -128,11 +130,11 @@ void TapeMeasure::OnReset() ///////////////////////////////////////////////// void TapeMeasure::Reset() { - this->DeleteMarker(this->dataPtr->startPointId); - this->DeleteMarker(this->dataPtr->endPointId); - this->DeleteMarker(this->dataPtr->lineId); + this->DeleteMarker(this->dataPtr->kStartPointId); + this->DeleteMarker(this->dataPtr->kEndPointId); + this->DeleteMarker(this->dataPtr->kLineId); - this->dataPtr->currentId = this->dataPtr->startPointId; + this->dataPtr->currentId = this->dataPtr->kStartPointId; this->dataPtr->startPoint = ignition::math::Vector3d::Zero; this->dataPtr->endPoint = ignition::math::Vector3d::Zero; this->dataPtr->distance = 0.0; @@ -223,9 +225,9 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) // If the user is currently choosing the end point, draw the connecting // line and update the new distance. - if (this->dataPtr->currentId == this->dataPtr->endPointId) + if (this->dataPtr->currentId == this->dataPtr->kEndPointId) { - this->DrawLine(this->dataPtr->lineId, this->dataPtr->startPoint, + this->DrawLine(this->dataPtr->kLineId, this->dataPtr->startPoint, point, this->dataPtr->hoverColor); this->dataPtr->distance = this->dataPtr->startPoint.Distance(point); this->newDistance(); @@ -245,7 +247,7 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) this->DrawPoint(this->dataPtr->currentId, point, this->dataPtr->drawColor); // If the user is placing the start point, update its position - if (this->dataPtr->currentId == this->dataPtr->startPointId) + if (this->dataPtr->currentId == this->dataPtr->kStartPointId) { this->dataPtr->startPoint = point; } @@ -255,14 +257,14 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) { this->dataPtr->endPoint = point; this->dataPtr->measure = false; - this->DrawLine(this->dataPtr->lineId, this->dataPtr->startPoint, + this->DrawLine(this->dataPtr->kLineId, this->dataPtr->startPoint, this->dataPtr->endPoint, this->dataPtr->drawColor); this->dataPtr->distance = this->dataPtr->startPoint.Distance(this->dataPtr->endPoint); this->newDistance(); QGuiApplication::restoreOverrideCursor(); } - this->dataPtr->currentId = this->dataPtr->endPointId; + this->dataPtr->currentId = this->dataPtr->kEndPointId; } } diff --git a/src/gui/plugins/tape_measure/TapeMeasure.hh b/src/gui/plugins/tape_measure/TapeMeasure.hh index 7d6417e30b..99e26cd5a1 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.hh +++ b/src/gui/plugins/tape_measure/TapeMeasure.hh @@ -17,6 +17,8 @@ #ifndef IGNITION_GAZEBO_GUI_TAPEMEASURE_HH_ #define IGNITION_GAZEBO_GUI_TAPEMEASURE_HH_ +#include + #include #include #include diff --git a/src/gui/plugins/tape_measure/TapeMeasure.qml b/src/gui/plugins/tape_measure/TapeMeasure.qml index 7b9453d348..3502b7fc93 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.qml +++ b/src/gui/plugins/tape_measure/TapeMeasure.qml @@ -103,6 +103,8 @@ ToolBar { } Text { text: qsTr(" Distance (m): " + distance.toFixed(3)) + font.pointSize: 14 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" } } } From 65d122ab3dec6a2f1b23c5c8068501c3eb277129 Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Tue, 24 Nov 2020 15:46:51 -0800 Subject: [PATCH 19/21] handle key presses on cpp side Signed-off-by: John Shepherd --- src/gui/plugins/tape_measure/TapeMeasure.cc | 29 ++++++++++++++++++-- src/gui/plugins/tape_measure/TapeMeasure.hh | 4 +++ src/gui/plugins/tape_measure/TapeMeasure.qml | 10 ------- 3 files changed, 31 insertions(+), 12 deletions(-) diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index 79174f7529..2642c052f3 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -41,7 +41,7 @@ namespace ignition::gazebo /// \brief Ignition communication node. public: transport::Node node; - /// \brief True if currently measure, else false. + /// \brief True if currently measuring, else false. public: bool measure = false; /// \brief The id of the start point marker. @@ -111,10 +111,18 @@ void TapeMeasure::LoadConfig(const tinyxml2::XMLElement *) ignition::gui::App()->findChild ()->installEventFilter(this); + ignition::gui::App()->findChild + ()->QuickWindow()->installEventFilter(this); } ///////////////////////////////////////////////// void TapeMeasure::OnMeasure() +{ + this->Measure(); +} + +///////////////////////////////////////////////// +void TapeMeasure::Measure() { this->Reset(); this->dataPtr->measure = true; @@ -267,7 +275,24 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) this->dataPtr->currentId = this->dataPtr->kEndPointId; } } - + else if (_event->type() == QEvent::KeyPress) + { + QKeyEvent *keyEvent = static_cast(_event); + if (keyEvent && keyEvent->key() == Qt::Key_M) + { + this->Reset(); + this->Measure(); + } + } + else if (_event->type() == QEvent::KeyRelease) + { + QKeyEvent *keyEvent = static_cast(_event); + if (keyEvent && keyEvent->key() == Qt::Key_Escape && + this->dataPtr->measure) + { + this->Reset(); + } + } return QObject::eventFilter(_obj, _event); } diff --git a/src/gui/plugins/tape_measure/TapeMeasure.hh b/src/gui/plugins/tape_measure/TapeMeasure.hh index 99e26cd5a1..0da8719f2b 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.hh +++ b/src/gui/plugins/tape_measure/TapeMeasure.hh @@ -53,6 +53,10 @@ namespace gazebo /// measurement. public: void Reset(); + /// \brief Starts a new measurement. Erases any previous measurement in + /// progress or already made. + public: void Measure(); + /// \brief Draws a point marker. Called to display the start and end /// point of the tape measure. /// \param[in] _id The id of the marker diff --git a/src/gui/plugins/tape_measure/TapeMeasure.qml b/src/gui/plugins/tape_measure/TapeMeasure.qml index 3502b7fc93..29362bcf09 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.qml +++ b/src/gui/plugins/tape_measure/TapeMeasure.qml @@ -34,11 +34,6 @@ ToolBar { distance = TapeMeasure.Distance(); } - function startMeasurement() { - TapeMeasure.OnReset(); - TapeMeasure.OnMeasure(); - } - Connections { target: TapeMeasure onNewDistance: { @@ -54,11 +49,6 @@ ToolBar { id: group } - Shortcut { - sequence: "M" - onActivated: startMeasurement() - } - RowLayout { spacing: 1 ToolButton { From a07db06a1862957d04d2c855516c7ea8edf1624f Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Fri, 11 Dec 2020 14:59:02 -0800 Subject: [PATCH 20/21] Update for new gui events Signed-off-by: John Shepherd --- src/gui/plugins/scene3d/Scene3D.cc | 12 ++++++------ src/gui/plugins/tape_measure/TapeMeasure.cc | 12 ++++++------ 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index e580b3a575..7b86d2c9bd 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -824,7 +824,7 @@ void IgnRenderer::BroadcastRightClick() math::Vector3d pos = this->ScreenToScene(this->dataPtr->mouseEvent.Pos()); - gui::events::RightClickToScene rightClickToSceneEvent(pos); + ignition::gui::events::RightClickToScene rightClickToSceneEvent(pos); ignition::gui::App()->sendEvent( ignition::gui::App()->findChild(), &rightClickToSceneEvent); @@ -2691,14 +2691,14 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) } } else if (_event->type() == - ignition::gazebo::gui::events::RightClickDropdownMenu::kType) + ignition::gui::events::DropdownMenuEnabled::kType) { - auto rightClickDropdownMenuEvent = - reinterpret_cast(_event); - if (rightClickDropdownMenuEvent) + auto dropdownMenuEnabledEvent = + reinterpret_cast(_event); + if (dropdownMenuEnabledEvent) { auto renderWindow = this->PluginItem()->findChild(); - renderWindow->SetRightClickMenu(rightClickDropdownMenuEvent->MenuEnabled()); + renderWindow->SetRightClickMenu(dropdownMenuEnabledEvent->MenuEnabled()); } } diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index 6cdc61e1a9..8129a1611f 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -130,10 +130,10 @@ void TapeMeasure::Measure() // Notify Scene3D to disable the right click menu while we use it to // cancel our current measuring action - gui::events::RightClickDropdownMenu rightClickDropdownMenuEvent(false); + ignition::gui::events::DropdownMenuEnabled dropdownMenuEnabledEvent(false); ignition::gui::App()->sendEvent( ignition::gui::App()->findChild(), - &rightClickDropdownMenuEvent); + &dropdownMenuEnabledEvent); } ///////////////////////////////////////////////// @@ -159,10 +159,10 @@ void TapeMeasure::Reset() // Notify Scene3D that we are done using the right click, so it can // re-enable the settings menu - gui::events::RightClickDropdownMenu rightClickDropdownMenuEvent(true); + ignition::gui::events::DropdownMenuEnabled dropdownMenuEnabledEvent(true); ignition::gui::App()->sendEvent( ignition::gui::App()->findChild(), - &rightClickDropdownMenuEvent); + &dropdownMenuEnabledEvent); } ///////////////////////////////////////////////// @@ -288,10 +288,10 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) // Notify Scene3D that we are done using the right click, so it can // re-enable the settings menu - gui::events::RightClickDropdownMenu rightClickDropdownMenuEvent(true); + ignition::gui::events::DropdownMenuEnabled dropdownMenuEnabledEvent(true); ignition::gui::App()->sendEvent( ignition::gui::App()->findChild(), - &rightClickDropdownMenuEvent); + &dropdownMenuEnabledEvent); } this->dataPtr->currentId = this->dataPtr->kEndPointId; } From 255a162fbc6114f196de2bdd899bb36517742eac Mon Sep 17 00:00:00 2001 From: John Shepherd Date: Mon, 28 Dec 2020 13:10:53 -0800 Subject: [PATCH 21/21] suggested fixes and lint Signed-off-by: John Shepherd --- src/gui/plugins/scene3d/Scene3D.cc | 20 +++++++++++--------- src/gui/plugins/scene3d/Scene3D.hh | 14 +++++++------- src/gui/plugins/tape_measure/TapeMeasure.cc | 4 +++- 3 files changed, 21 insertions(+), 17 deletions(-) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 6cfdd4e05b..b6e3dc9af1 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -264,9 +264,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// resource with the shapes plugin or not public: bool isPlacing = false; - /// \brief Atomic bool indicating whether the right click menu + /// \brief Atomic bool indicating whether the dropdown menu /// is currently enabled or disabled. - public: std::atomic_bool rightClickMenuEnabled = true; + public: std::atomic_bool dropdownMenuEnabled = true; /// \brief The SDF string of the resource to be used with plugins that spawn /// entities. @@ -948,8 +948,8 @@ void IgnRenderer::BroadcastRightClick() this->dataPtr->mouseEvent.Type() == common::MouseEvent::RELEASE && !this->dataPtr->mouseEvent.Dragging() && this->dataPtr->mouseDirty) { - // If the right click menu is disabled, quash the mouse event - if (!this->dataPtr->rightClickMenuEnabled) + // If the dropdown menu is disabled, quash the mouse event + if (!this->dataPtr->dropdownMenuEnabled) this->dataPtr->mouseDirty = false; math::Vector3d pos = this->ScreenToScene(this->dataPtr->mouseEvent.Pos()); @@ -1847,9 +1847,9 @@ void IgnRenderer::SetModelPath(const std::string &_filePath) } ///////////////////////////////////////////////// -void IgnRenderer::SetRightClickMenu(bool _enableRightClickMenu) +void IgnRenderer::SetDropdownMenuEnabled(bool _enableDropdownMenu) { - this->dataPtr->rightClickMenuEnabled = _enableRightClickMenu; + this->dataPtr->dropdownMenuEnabled = _enableDropdownMenu; } ///////////////////////////////////////////////// @@ -2940,7 +2940,8 @@ bool Scene3D::eventFilter(QObject *_obj, QEvent *_event) if (dropdownMenuEnabledEvent) { auto renderWindow = this->PluginItem()->findChild(); - renderWindow->SetRightClickMenu(dropdownMenuEnabledEvent->MenuEnabled()); + renderWindow->SetDropdownMenuEnabled( + dropdownMenuEnabledEvent->MenuEnabled()); } } @@ -2975,9 +2976,10 @@ void RenderWindowItem::SetModelPath(const std::string &_filePath) } ///////////////////////////////////////////////// -void RenderWindowItem::SetRightClickMenu(bool _enableRightClickMenu) +void RenderWindowItem::SetDropdownMenuEnabled(bool _enableDropdownMenu) { - this->dataPtr->renderThread->ignRenderer.SetRightClickMenu(_enableRightClickMenu); + this->dataPtr->renderThread->ignRenderer.SetDropdownMenuEnabled( + _enableDropdownMenu); } ///////////////////////////////////////////////// diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index 6beae5d03f..cf966a4efe 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -199,10 +199,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \param[in] _filePath Sdf path of the model to load in for the user. public: void SetModelPath(const std::string &_filePath); - /// \brief Set if the right click menu is enabled or disabled. - /// \param[in] _enableRightClickMenu The boolean to enable or disable - /// the menu - public: void SetRightClickMenu(bool _enableRightClickMenu); + /// \brief Set if the dropdown menu is enabled or disabled. + /// \param[in] _enableDropdownMenu The boolean to enable or disable + /// the dropdown menu + public: void SetDropdownMenuEnabled(bool _enableDropdownMenu); /// \brief Set whether to record video /// \param[in] _record True to start video recording, false to stop. @@ -534,10 +534,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \param[in] _filePath File path of the model to load in for the user. public: void SetModelPath(const std::string &_filePath); - /// \brief Set if the right click menu is enabled or disabled. - /// \param[in] _enableRightClickMenu The boolean to enable or disable + /// \brief Set if the dropdown menu is enabled or disabled. + /// \param[in] _enableDropdownMenu The boolean to enable or disable /// the menu - public: void SetRightClickMenu(bool _enableRightClickMenu); + public: void SetDropdownMenuEnabled(bool _enableDropdownMenu); /// \brief Set whether to record video /// \param[in] _record True to start video recording, false to stop. diff --git a/src/gui/plugins/tape_measure/TapeMeasure.cc b/src/gui/plugins/tape_measure/TapeMeasure.cc index de4fc03231..882ce7e9c3 100644 --- a/src/gui/plugins/tape_measure/TapeMeasure.cc +++ b/src/gui/plugins/tape_measure/TapeMeasure.cc @@ -288,7 +288,9 @@ bool TapeMeasure::eventFilter(QObject *_obj, QEvent *_event) // Notify Scene3D that we are done using the right click, so it can // re-enable the settings menu - ignition::gui::events::DropdownMenuEnabled dropdownMenuEnabledEvent(true); + ignition::gui::events::DropdownMenuEnabled + dropdownMenuEnabledEvent(true); + ignition::gui::App()->sendEvent( ignition::gui::App()->findChild(), &dropdownMenuEnabledEvent);