Ignition Gazebo

API Reference

6.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 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...
 

Signals

void CamClipDistChanged ()
 Notify that the gui camera's near/far clipping distances changed. More...
 
void CamPoseChanged ()
 Notify that the gui camera pose 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...
 
void LoadConfig (const tinyxml2::XMLElement *_pluginElem) override
 

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...
 

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()

~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.

◆ 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.

◆ 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.

◆ OnViewControl

void OnViewControl ( const QString &  _controller)
slot

Callback in Qt thread when camera view controller changes.

Parameters
[in]_modeNew camera view controller

◆ 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

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)


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