ViewAngle.hh
Go to the documentation of this file.
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.
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.