30 #include <OgreViewport.h> 31 #include <OgreQuaternion.h> 32 #include <OgreVector3.h> 33 #include <OgreSceneNode.h> 34 #include <OgreSceneManager.h> 35 #include <OgreCamera.h> 51 Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Y) *
52 Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Z);
63 new VectorProperty(
"Position", Ogre::Vector3(5, 5, 10),
"Position of the camera.",
this);
75 camera_->setProjectionType(Ogre::PT_PERSPECTIVE);
80 camera_->setPosition(Ogre::Vector3(5, 5, 10));
90 setStatus(
"<b>Left-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z.");
94 setStatus(
"<b>Left-Click:</b> Rotate. <b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z. " 95 " <b>Shift</b>: More options.");
101 if (event.
type == QEvent::MouseMove)
103 diff_x =
event.x -
event.last_x;
104 diff_y =
event.y -
event.last_y;
106 bool moved = diff_x != 0 || diff_y != 0;
108 if (event.
left() && !
event.shift())
111 yaw(-diff_x * 0.005);
112 pitch(diff_y * 0.005);
114 else if (event.
middle() || (
event.shift() &&
event.left()))
117 move(diff_x * 0.01, -diff_y * 0.01, 0.0
f);
119 else if (event.
right())
122 move(0.0
f, 0.0
f, diff_y * 0.1);
132 int diff =
event.wheel_delta;
133 move(0.0
f, 0.0
f, -diff * 0.01);
145 Ogre::Quaternion quat = source_camera->getOrientation() * ROBOT_TO_CAMERA_ROTATION.Inverse();
147 quat =
camera_->getOrientation() * Ogre::Quaternion(-quat.getRoll(
false), Ogre::Vector3::UNIT_Z) *
148 ROBOT_TO_CAMERA_ROTATION.Inverse();
157 Ogre::Vector3 direction = quat * Ogre::Vector3::NEGATIVE_UNIT_Z;
159 if (direction.dotProduct(Ogre::Vector3::NEGATIVE_UNIT_Z) < 0)
161 if (pitch > Ogre::Math::HALF_PI)
163 pitch -= Ogre::Math::PI;
165 else if (pitch < -Ogre::Math::HALF_PI)
167 pitch += Ogre::Math::PI;
172 if (direction.dotProduct(Ogre::Vector3::UNIT_X) < 0)
174 yaw -= Ogre::Math::PI;
178 yaw += Ogre::Math::PI;
206 const Ogre::Quaternion& )
239 Ogre::Vector3 translate(x, y, z);
Ogre::Quaternion getOrientation()
Return a Quaternion based on the yaw and pitch properties.
virtual bool setVector(const Ogre::Vector3 &vector)
void handleMouseEvent(ViewportMouseEvent &evt) override
FloatProperty * pitch_property_
The camera's pitch (rotation around the x-axis), in radians.
A first-person camera, controlled by yaw, pitch, and position.
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
void setCursor(CursorType cursor_type)
Ogre::Camera * getCamera() const
VectorProperty * position_property_
virtual Ogre::Vector3 getVector() const
Property specialized to enforce floating point max/min.
bool add(const Ogre::Vector3 &offset)
float mapAngleTo0_2Pi(float angle)
Return the input angle mapped back to the range 0 to 2*PI.
void onInitialize() override
Do subclass-specific initialization.
bool add(float delta)
Add the given delta to the property value.
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
void move(float x, float y, float z)
Ogre::Vector3 reference_position_
void setPropertiesFromCamera(Ogre::Camera *source_camera)
void onInitialize() override
Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ ...
void setStatus(const QString &message)
~FPSViewController() override
void onTargetFrameChanged(const Ogre::Vector3 &old_reference_position, const Ogre::Quaternion &old_reference_orientation) override
Override to implement the change in properties which nullifies the change in target frame...
void update(float dt, float ros_dt) override
Called at 30Hz by ViewManager::update() while this view is active. Override with code that needs to r...
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
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...
virtual float getFloat() const
FloatProperty * yaw_property_
The camera's yaw (rotation around the y-axis), in radians.
Ogre::SceneNode * target_scene_node_
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 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 hide()
Hide this Property in any PropertyTreeWidgets.
DisplayContext * context_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION
void update(float dt, float ros_dt) override
Called at 30Hz by ViewManager::update() while this view is active. Override with code that needs to r...