Ignition Gazebo

API Reference

3.5.0
TapeMeasure.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2020 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef IGNITION_GAZEBO_GUI_TAPEMEASURE_HH_
18 #define IGNITION_GAZEBO_GUI_TAPEMEASURE_HH_
19 
20 #include <memory>
21 
22 #include <ignition/gui/Plugin.hh>
23 #include <ignition/math/Vector3.hh>
24 #include <ignition/math/Color.hh>
25 
26 namespace ignition
27 {
28 namespace gazebo
29 {
30  class TapeMeasurePrivate;
31 
33  class TapeMeasure : public ignition::gui::Plugin
34  {
35  Q_OBJECT
36 
38  public: TapeMeasure();
39 
41  public: ~TapeMeasure() override;
42 
43  // Documentation inherited
44  public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override;
45 
49  public: void DeleteMarker(int _id);
50 
54  public: void Reset();
55 
58  public: void Measure();
59 
65  public: void DrawPoint(int _id,
67  ignition::math::Color &_color);
68 
75  public: void DrawLine(int _id,
76  ignition::math::Vector3d &_startPoint,
77  ignition::math::Vector3d &_endPoint,
78  ignition::math::Color &_color);
79 
82  public slots: void OnMeasure();
83 
85  public slots: void OnReset();
86 
90  public slots: double Distance();
91 
92  // Documentation inherited
93  protected: bool eventFilter(QObject *_obj, QEvent *_event) override;
94 
96  signals: void newDistance();
97 
100  private: std::unique_ptr<TapeMeasurePrivate> dataPtr;
101  };
102 }
103 }
104 
105 #endif
void Measure()
Starts a new measurement. Erases any previous measurement in progress or already made.
double Distance()
Callback in Qt thread to get the distance to display in the gui window.
void OnMeasure()
Callback in Qt thread when the new measurement button is clicked.
void newDistance()
Signal fired when a new tape measure distance is set.
void Reset()
Resets all of the relevant data for this plugin. Called when the user clicks the reset button and whe...
~TapeMeasure() override
Destructor.
void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override
Provides buttons for the tape measure tool.
Definition: TapeMeasure.hh:33
void DeleteMarker(int _id)
Deletes the marker with the provided id within the "tape_measure" namespace.
bool eventFilter(QObject *_obj, QEvent *_event) override
void DrawPoint(int _id, ignition::math::Vector3d &_point, ignition::math::Color &_color)
Draws a point marker. Called to display the start and end point of the tape measure.
This library is part of the Ignition Robotics project.
void DrawLine(int _id, ignition::math::Vector3d &_startPoint, ignition::math::Vector3d &_endPoint, ignition::math::Color &_color)
Draws a line marker. Called to display the line between the start and end point of the tape measure...
void OnReset()
Callback in Qt thread when the reset button is clicked.