Provides buttons for viewing angles. More...
#include <ViewAngle.hh>
Public Slots | |
void | OnAngleMode (int _x, int _y, int _z) |
Callback in Qt thread when angle mode changes. More... | |
void | OnViewControl (const QString &_controller) |
Callback in Qt thread when camera view controller changes. More... | |
void | OnViewControlReferenceVisual (bool _enable) |
Callback in Qt thread when camera view reference visual state changes. More... | |
void | OnViewControlSensitivity (double _sensitivity) |
Callback in Qt thread when camera view controller changes. More... | |
void | SetCamClipDist (double _near, double _far) |
Updates gui camera's near/far clipping distances. More... | |
void | SetCamPose (double _x, double _y, double _z, double _roll, double _pitch, double _yaw) |
Callback to update gui camera pose. More... | |
void | SetHorizontalFOV (double _horizontalFOV) |
Updates gui camera's Horizontal fov. More... | |
Signals | |
void | CamClipDistChanged () |
Notify that the gui camera's near/far clipping distances changed. More... | |
void | CamHorizontalFOVChanged () |
Notify that the gui camera's horizontal fov changed. More... | |
void | CamPoseChanged () |
Notify that the gui camera pose has changed. More... | |
void | ViewControlIndexChanged () |
Notify that the camera's view controller has changed. More... | |
Public Member Functions | |
ViewAngle () | |
Constructor. More... | |
~ViewAngle () override | |
Destructor. More... | |
Q_INVOKABLE QList< double > | CamClipDist () const |
Get the current gui camera's near and far clipping distances. More... | |
Q_INVOKABLE QList< double > | CamPose () const |
Get the current gui camera pose. More... | |
void | CamPoseCb (const msgs::Pose &_msg) |
Callback for retrieving gui camera pose. More... | |
Q_INVOKABLE double | HorizontalFOV () const |
Get the current gui horizontal fov. More... | |
void | LoadConfig (const tinyxml2::XMLElement *_pluginElem) override |
bool | OnMoveToModelService (const ignition::msgs::GUICamera &_msg, ignition::msgs::Boolean &_res) |
Move to model service received. More... | |
int | ViewControlIndex () const |
Get the current index for view controller (on qml side) More... | |
Properties | |
QList< double > | camClipDist |
gui camera near/far clipping distance (QList order is near, far) More... | |
QList< double > | camPose |
gui camera pose (QList order is x, y, z, roll, pitch, yaw) More... | |
double | horizontalFOV |
gui camera horizontal fov More... | |
int | viewControlIndex |
view controller index for qml side (0: orbit; 1: ortho) More... | |
Detailed Description
Provides buttons for viewing angles.
Configuration
<service> : Set the service to receive view angle requests. <legacy> : Set to true to use with GzScene3D, false to use with MinimalScene. Defaults to true.
Constructor & Destructor Documentation
◆ ViewAngle()
ViewAngle | ( | ) |
Constructor.
◆ ~ViewAngle()
|
override |
Destructor.
Member Function Documentation
◆ CamClipDist()
Q_INVOKABLE QList<double> CamClipDist | ( | ) | const |
Get the current gui camera's near and far clipping distances.
◆ CamClipDistChanged
|
signal |
Notify that the gui camera's near/far clipping distances changed.
◆ CamHorizontalFOVChanged
|
signal |
Notify that the gui camera's horizontal fov changed.
◆ CamPose()
Q_INVOKABLE QList<double> CamPose | ( | ) | const |
Get the current gui camera pose.
◆ CamPoseCb()
void CamPoseCb | ( | const msgs::Pose & | _msg | ) |
Callback for retrieving gui camera pose.
- Parameters
-
[in] _msg Pose message
◆ CamPoseChanged
|
signal |
Notify that the gui camera pose has changed.
◆ HorizontalFOV()
Q_INVOKABLE double HorizontalFOV | ( | ) | const |
Get the current gui horizontal fov.
◆ LoadConfig()
|
override |
◆ OnAngleMode
|
slot |
Callback in Qt thread when angle mode changes.
- Parameters
-
[in] _x The x component of the directional vector for the camera to assume. All 0s for x, y, and z indicate the initial camera pose. [in] _y The y component of the directional vector for the camera to assume. All 0s for x, y, and z indicate the initial camera pose. [in] _z The z component of the directional vector for the camera to assume. All 0s for x, y, and z indicate the initial camera pose.
◆ OnMoveToModelService()
bool OnMoveToModelService | ( | const ignition::msgs::GUICamera & | _msg, |
ignition::msgs::Boolean & | _res | ||
) |
Move to model service received.
- Parameters
-
[in] _msg GUI camera message [in] _res Response
◆ OnViewControl
|
slot |
Callback in Qt thread when camera view controller changes.
- Parameters
-
[in] _mode New camera view controller
◆ OnViewControlReferenceVisual
|
slot |
Callback in Qt thread when camera view reference visual state changes.
- Parameters
-
[in] _enable True to enable camera view control reference visual, false to hide it
◆ OnViewControlSensitivity
|
slot |
Callback in Qt thread when camera view controller changes.
- Parameters
-
[in] _sensitivity View control sensitivity vlaue
◆ SetCamClipDist
|
slot |
Updates gui camera's near/far clipping distances.
- Parameters
-
[in] _near Near clipping plane distance [in] _far Far clipping plane distance
◆ SetCamPose
|
slot |
Callback to update gui camera pose.
- Parameters
-
[in] _x,_y,_z cartesion coordinates [in] _roll,_pitch,_yaw principal coordinates
◆ SetHorizontalFOV
|
slot |
Updates gui camera's Horizontal fov.
- Parameters
-
[in] _horizontalFOV Horizontal fov
◆ ViewControlIndex()
int ViewControlIndex | ( | ) | const |
Get the current index for view controller (on qml side)
◆ ViewControlIndexChanged
|
signal |
Notify that the camera's view controller has changed.
Property Documentation
◆ camClipDist
|
read |
gui camera near/far clipping distance (QList order is near, far)
◆ camPose
|
read |
gui camera pose (QList order is x, y, z, roll, pitch, yaw)
◆ horizontalFOV
|
read |
gui camera horizontal fov
◆ viewControlIndex
|
read |
view controller index for qml side (0: orbit; 1: ortho)
The documentation for this class was generated from the following file: