Gazebo Gazebo

API Reference

6.16.0
ViewAngle.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 
18 #ifndef GZ_GAZEBO_GUI_VIEWANGLE_HH_
19 #define GZ_GAZEBO_GUI_VIEWANGLE_HH_
20 
21 #include <gz/msgs/pose.pb.h>
22 #include <gz/msgs/boolean.pb.h>
23 #include <gz/msgs/gui_camera.pb.h>
24 
25 #include <memory>
26 
27 #include <gz/gui/Plugin.hh>
28 
29 namespace ignition
30 {
31 namespace gazebo
32 {
33  class ViewAnglePrivate;
34 
41  class ViewAngle : public gz::gui::Plugin
42  {
43  Q_OBJECT
44 
46  Q_PROPERTY(
47  QList<double> camPose
48  READ CamPose
49  NOTIFY CamPoseChanged
50  )
51 
52 
53  Q_PROPERTY(
54  QList<double> camClipDist
55  READ CamClipDist
56  NOTIFY CamClipDistChanged
57  )
58 
60  Q_PROPERTY(
62  READ ViewControlIndex
64  )
65 
67  Q_PROPERTY(
68  double horizontalFOV
69  READ HorizontalFOV
71  )
72 
74  public: ViewAngle();
75 
77  public: ~ViewAngle() override;
78 
79  // Documentation inherited
80  public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override;
81 
82  // Documentation inherited
83  private: bool eventFilter(QObject *_obj, QEvent *_event) override;
84 
92  public slots: void OnAngleMode(int _x, int _y, int _z);
93 
96  public slots: void OnViewControl(const QString &_controller);
97 
102  public slots: void OnViewControlReferenceVisual(bool _enable);
103 
106  public slots: void OnViewControlSensitivity(double _sensitivity);
107 
110  public slots: void SetHorizontalFOV(double _horizontalFOV);
111 
113  public: Q_INVOKABLE double HorizontalFOV() const;
114 
116  signals: void CamHorizontalFOVChanged();
117 
119  public: Q_INVOKABLE QList<double> CamPose() const;
120 
122  signals: void CamPoseChanged();
123 
127  public slots: void SetCamPose(double _x, double _y, double _z,
128  double _roll, double _pitch, double _yaw);
129 
132  public: void CamPoseCb(const msgs::Pose &_msg);
133 
137  public: bool OnMoveToModelService(const ignition::msgs::GUICamera &_msg,
138  ignition::msgs::Boolean &_res);
139 
141  public: Q_INVOKABLE QList<double> CamClipDist() const;
142 
144  signals: void CamClipDistChanged();
145 
149  public slots: void SetCamClipDist(double _near, double _far);
150 
152  public: int ViewControlIndex() const;
153 
155  signals: void ViewControlIndexChanged();
156 
159  private: std::unique_ptr<ViewAnglePrivate> dataPtr;
160  };
161 }
162 }
163 
164 #endif
void SetCamPose(double _x, double _y, double _z, double _roll, double _pitch, double _yaw)
Callback to update gui camera pose.
This library is part of the Gazebo project.
Q_INVOKABLE QList< double > CamPose() const
Get the current gui camera pose.
double horizontalFOV
gui camera horizontal fov
Definition: ViewAngle.hh:71
QList< double > camPose
gui camera pose (QList order is x, y, z, roll, pitch, yaw)
Definition: ViewAngle.hh:50
void OnViewControlReferenceVisual(bool _enable)
Callback in Qt thread when camera view reference visual state changes.
void CamPoseCb(const msgs::Pose &_msg)
Callback for retrieving gui camera pose.
Q_INVOKABLE double HorizontalFOV() const
Get the current gui horizontal fov.
void OnAngleMode(int _x, int _y, int _z)
Callback in Qt thread when angle mode changes.
void CamHorizontalFOVChanged()
Notify that the gui camera's horizontal fov changed.
int viewControlIndex
view controller index for qml side (0: orbit; 1: ortho)
Definition: ViewAngle.hh:64
Q_INVOKABLE QList< double > CamClipDist() const
Get the current gui camera's near and far clipping distances.
void OnViewControl(const QString &_controller)
Callback in Qt thread when camera view controller changes.
Component< gz::math::Pose3d, class PoseTag > Pose
A component type that contains pose, gz::math::Pose3d, information.
Definition: gz/sim/components/Pose.hh:35
void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override
bool OnMoveToModelService(const ignition::msgs::GUICamera &_msg, ignition::msgs::Boolean &_res)
Move to model service received.
Provides buttons for viewing angles.
Definition: ViewAngle.hh:41
void CamPoseChanged()
Notify that the gui camera pose has changed.
void ViewControlIndexChanged()
Notify that the camera's view controller has changed.
void SetCamClipDist(double _near, double _far)
Updates gui camera's near/far clipping distances.
void OnViewControlSensitivity(double _sensitivity)
Callback in Qt thread when camera view controller changes.
STL namespace.
QList< double > camClipDist
gui camera near/far clipping distance (QList order is near, far)
Definition: ViewAngle.hh:57
void SetHorizontalFOV(double _horizontalFOV)
Updates gui camera's Horizontal fov.
int ViewControlIndex() const
Get the current index for view controller (on qml side)
void CamClipDistChanged()
Notify that the gui camera's near/far clipping distances changed.