Ignition Gazebo

API Reference

6.1.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 IGNITION_GAZEBO_GUI_VIEWANGLE_HH_
19 #define IGNITION_GAZEBO_GUI_VIEWANGLE_HH_
20 
21 #include <ignition/msgs/pose.pb.h>
22 
23 #include <memory>
24 
25 #include <ignition/gui/Plugin.hh>
26 
27 namespace ignition
28 {
29 namespace gazebo
30 {
31  class ViewAnglePrivate;
32 
39  class ViewAngle : public ignition::gui::Plugin
40  {
41  Q_OBJECT
42 
44  Q_PROPERTY(
45  QList<double> camPose
46  READ CamPose
47  NOTIFY CamPoseChanged
48  )
49 
50 
51  Q_PROPERTY(
52  QList<double> camClipDist
53  READ CamClipDist
54  NOTIFY CamClipDistChanged
55  )
56 
58  public: ViewAngle();
59 
61  public: ~ViewAngle() override;
62 
63  // Documentation inherited
64  public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override;
65 
66  // Documentation inherited
67  private: bool eventFilter(QObject *_obj, QEvent *_event) override;
68 
76  public slots: void OnAngleMode(int _x, int _y, int _z);
77 
80  public slots: void OnViewControl(const QString &_controller);
81 
83  public: Q_INVOKABLE QList<double> CamPose() const;
84 
86  signals: void CamPoseChanged();
87 
91  public slots: void SetCamPose(double _x, double _y, double _z,
92  double _roll, double _pitch, double _yaw);
93 
96  public: void CamPoseCb(const msgs::Pose &_msg);
97 
99  public: Q_INVOKABLE QList<double> CamClipDist() const;
100 
102  signals: void CamClipDistChanged();
103 
107  public slots: void SetCamClipDist(double _near, double _far);
108 
111  private: std::unique_ptr<ViewAnglePrivate> dataPtr;
112  };
113 }
114 }
115 
116 #endif
void SetCamClipDist(double _near, double _far)
Updates gui camera&#39;s near/far clipping distances.
Q_INVOKABLE QList< double > CamPose() const
Get the current gui camera pose.
QList< double > camPose
gui camera pose (QList order is x, y, z, roll, pitch, yaw)
Definition: ViewAngle.hh:48
void OnViewControl(const QString &_controller)
Callback in Qt thread when camera view controller changes.
void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override
STL namespace.
Q_INVOKABLE QList< double > CamClipDist() const
Get the current gui camera&#39;s near and far clipping distances.
void SetCamPose(double _x, double _y, double _z, double _roll, double _pitch, double _yaw)
Callback to update gui camera pose.
void CamPoseCb(const msgs::Pose &_msg)
Callback for retrieving gui camera pose.
void OnAngleMode(int _x, int _y, int _z)
Callback in Qt thread when angle mode changes.
Component< ignition::math::Pose3d, class PoseTag > Pose
A component type that contains pose, ignition::math::Pose3d, information.
Definition: Pose.hh:35
QList< double > camClipDist
gui camera near/far clipping distance (QList order is near, far)
Definition: ViewAngle.hh:55
This library is part of the Ignition Robotics project.