frame_view_controller.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019, Bielefeld University
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Bielefeld University nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef RVIZ_FRAME_VIEW_CONTROLLER_H
31 #define RVIZ_FRAME_VIEW_CONTROLLER_H
32 
34 
35 namespace rviz
36 {
37 class FloatProperty;
38 class VectorProperty;
39 class EnumProperty;
40 
43 {
44  Q_OBJECT
45 
46 public:
48  ~FrameViewController() override = default;
49  void onInitialize() override;
50 
51  void reset() override;
52  void mimic(ViewController* source_view) override;
53  void lookAt(const Ogre::Vector3& point) override;
54  void handleMouseEvent(ViewportMouseEvent& event) override;
55 
56  void move(float x, float y, float z);
57  void rotate(float yaw, float pitch, float roll);
58 
59 protected:
60  void onTargetFrameChanged(const Ogre::Vector3& /* old_reference_position */,
61  const Ogre::Quaternion& /* old_reference_orientation */) override;
62  void updateTargetSceneNode() override;
63 
64  Ogre::Quaternion getOrientation(float yaw, float pitch, float roll);
68  void setAxisFromCamera();
70  int actualCameraAxisOption(double precision = 0.001) const;
71 
78 
79 protected Q_SLOTS:
80  void changedPosition();
81  void changedOrientation();
82  void changedAxis();
83 
84 private:
85  void rememberAxis(int current);
87 };
88 
89 } // end namespace rviz
90 
91 #endif // RVIZ_FRAME_VIEW_CONTROLLER_H
~FrameViewController() override=default
int actualCameraAxisOption(double precision=0.001) const
find enum ID from camera's current pose
BoolProperty * locked_property_
Lock camera, i.e. disable mouse interaction?
void move(float x, float y, float z)
Base class of ViewControllers which have a "Target Frame" which is a TF frame whose position they tra...
void rotate(float yaw, float pitch, float roll)
FloatProperty * pitch_property_
The camera's pitch (rotation around the y-axis), in radians.
Property specialized to enforce floating point max/min.
Ogre::Quaternion getOrientation(float yaw, float pitch, float roll)
VectorProperty * position_property_
The camera's position.
void updateTargetSceneNode() override
Update the position of the target_scene_node_ from the TF frame specified in the Target Frame propert...
FloatProperty * roll_property_
The camera's roll (rotation around the x-axis), in radians.
FloatProperty * yaw_property_
The camera's yaw (rotation around the z-axis), in radians.
void handleMouseEvent(ViewportMouseEvent &event) override
void setPropertiesFromCamera()
set yaw, pitch, roll, position properties from camera
EnumProperty * axis_property_
The axis that the camera aligns to.
void mimic(ViewController *source_view) override
Configure the settings of this view controller to give, as much as possible, a similar view as that g...
void onInitialize() override
Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ ...
A camera tied to a given frame.
Property specialized to provide getter for booleans.
Definition: bool_property.h:38
void onTargetFrameChanged(const Ogre::Vector3 &, const Ogre::Quaternion &) override
Override to implement the change in properties which nullifies the change in target frame...
void lookAt(const Ogre::Vector3 &point) override
This should be implemented in each subclass to aim the camera at the given point in space (relative t...
void setAxisFromCamera()
set axis_property_ from camera
Enum property.
Definition: enum_property.h:46


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:24