Gazebo Sim

API Reference

7.9.0

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 gz::msgs::GUICamera &_msg, gz::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. MinimalScene. Defaults to true.

Constructor & Destructor Documentation

◆ ViewAngle()

ViewAngle ( )

Constructor.

◆ ~ViewAngle()

~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

void CamClipDistChanged ( )
signal

Notify that the gui camera's near/far clipping distances changed.

◆ CamHorizontalFOVChanged

void 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]_msgPose message

◆ CamPoseChanged

void CamPoseChanged ( )
signal

Notify that the gui camera pose has changed.

◆ HorizontalFOV()

Q_INVOKABLE double HorizontalFOV ( ) const

Get the current gui horizontal fov.

◆ LoadConfig()

void LoadConfig ( const tinyxml2::XMLElement *  _pluginElem)
override

◆ OnAngleMode

void OnAngleMode ( int  _x,
int  _y,
int  _z 
)
slot

Callback in Qt thread when angle mode changes.

Parameters
[in]_xThe x component of the directional vector for the camera to assume. All 0s for x, y, and z indicate the initial camera pose.
[in]_yThe y component of the directional vector for the camera to assume. All 0s for x, y, and z indicate the initial camera pose.
[in]_zThe 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 gz::msgs::GUICamera _msg,
gz::msgs::Boolean _res 
)

Move to model service received.

Parameters
[in]_msgGUI camera message
[in]_resResponse

◆ OnViewControl

void OnViewControl ( const QString &  _controller)
slot

Callback in Qt thread when camera view controller changes.

Parameters
[in]_modeNew camera view controller

◆ OnViewControlReferenceVisual

void OnViewControlReferenceVisual ( bool  _enable)
slot

Callback in Qt thread when camera view reference visual state changes.

Parameters
[in]_enableTrue to enable camera view control reference visual, false to hide it

◆ OnViewControlSensitivity

void OnViewControlSensitivity ( double  _sensitivity)
slot

Callback in Qt thread when camera view controller changes.

Parameters
[in]_sensitivityView control sensitivity vlaue

◆ SetCamClipDist

void SetCamClipDist ( double  _near,
double  _far 
)
slot

Updates gui camera's near/far clipping distances.

Parameters
[in]_nearNear clipping plane distance
[in]_farFar clipping plane distance

◆ SetCamPose

void SetCamPose ( double  _x,
double  _y,
double  _z,
double  _roll,
double  _pitch,
double  _yaw 
)
slot

Callback to update gui camera pose.

Parameters
[in]_x,_y,_zcartesion coordinates
[in]_roll,_pitch,_yawprincipal coordinates

◆ SetHorizontalFOV

void SetHorizontalFOV ( double  _horizontalFOV)
slot

Updates gui camera's Horizontal fov.

Parameters
[in]_horizontalFOVHorizontal fov

◆ ViewControlIndex()

int ViewControlIndex ( ) const

Get the current index for view controller (on qml side)

◆ ViewControlIndexChanged

void ViewControlIndexChanged ( )
signal

Notify that the camera's view controller has changed.

Property Documentation

◆ camClipDist

QList<double> camClipDist
read

gui camera near/far clipping distance (QList order is near, far)

◆ camPose

QList<double> camPose
read

gui camera pose (QList order is x, y, z, roll, pitch, yaw)

◆ horizontalFOV

double horizontalFOV
read

gui camera horizontal fov

◆ viewControlIndex

int viewControlIndex
read

view controller index for qml side (0: orbit; 1: ortho)


The documentation for this class was generated from the following file: