30 #include <OgreViewport.h> 31 #include <OgreQuaternion.h> 32 #include <OgreVector3.h> 33 #include <OgreSceneNode.h> 34 #include <OgreSceneManager.h> 35 #include <OgreCamera.h> 52 Ogre::Quaternion( Ogre::Radian( -Ogre::Math::HALF_PI ), Ogre::Vector3::UNIT_Y ) *
53 Ogre::Quaternion( Ogre::Radian( -Ogre::Math::HALF_PI ), Ogre::Vector3::UNIT_Z );
76 camera_->setProjectionType( Ogre::PT_PERSPECTIVE );
82 camera_->setPosition( Ogre::Vector3( 5, 5, 10 ));
99 setStatus(
"<b>Left-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z." );
103 setStatus(
"<b>Left-Click:</b> Rotate. <b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Zoom. <b>Shift</b>: More options." );
111 if( event.
type == QEvent::MouseMove )
113 diff_x =
event.x -
event.last_x;
114 diff_y =
event.y -
event.last_y;
118 if( event.
left() && !
event.shift() )
121 yaw( -diff_x*0.005 );
122 pitch( diff_y*0.005 );
124 else if( event.
middle() || (
event.shift() &&
event.left() ))
127 move( diff_x*0.01, -diff_y*0.01, 0.0
f );
129 else if( event.
right() )
132 move( 0.0
f, 0.0
f, diff_y*0.1 );
141 int diff =
event.wheel_delta;
142 move( 0.0
f, 0.0
f, -diff * 0.01 );
155 Ogre::Quaternion quat = source_camera->getOrientation() * ROBOT_TO_CAMERA_ROTATION.Inverse();
156 float yaw = quat.getRoll(
false ).valueRadians();
157 float pitch = quat.getYaw(
false ).valueRadians();
159 Ogre::Vector3 direction = quat * Ogre::Vector3::NEGATIVE_UNIT_Z;
161 if ( direction.dotProduct( Ogre::Vector3::NEGATIVE_UNIT_Z ) < 0 )
163 if ( pitch > Ogre::Math::HALF_PI )
165 pitch -= Ogre::Math::PI;
167 else if ( pitch < -Ogre::Math::HALF_PI )
169 pitch += Ogre::Math::PI;
174 if ( direction.dotProduct( Ogre::Vector3::UNIT_X ) < 0 )
176 yaw -= Ogre::Math::PI;
180 yaw += Ogre::Math::PI;
240 Ogre::Vector3 translate( x, y, z );
Ogre::Quaternion getOrientation()
Return a Quaternion based on the yaw and pitch properties.
virtual void mimic(ViewController *source_view)
Configure the settings of this view controller to give, as much as possible, a similar view as that g...
virtual void onInitialize()
Do subclass-specific initialization. Called by ViewController::initialize after context_, target_scene_node_, and camera_ are set. This version calls updateTargetSceneNode().
virtual bool setVector(const Ogre::Vector3 &vector)
FloatProperty * pitch_property_
The camera's pitch (rotation around the x-axis), in radians.
A first-person camera, controlled by yaw, pitch, and position.
virtual ~FPSViewController()
virtual void lookAt(const Ogre::Vector3 &point)
This should be implemented in each subclass to aim the camera at the given point in space (relative t...
void setCursor(CursorType cursor_type)
virtual float getFloat() const
VectorProperty * position_property_
Property specialized to enforce floating point max/min.
virtual void handleMouseEvent(ViewportMouseEvent &evt)
bool add(const Ogre::Vector3 &offset)
virtual void onTargetFrameChanged(const Ogre::Vector3 &old_reference_position, const Ogre::Quaternion &old_reference_orientation)
Override to implement the change in properties which nullifies the change in target frame...
float mapAngleTo0_2Pi(float angle)
Return the input angle mapped back to the range 0 to 2*PI.
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_
virtual void update(float dt, float ros_dt)
Called at 30Hz by ViewManager::update() while this view is active. Override with code that needs to r...
void setPropertiesFromCamera(Ogre::Camera *source_camera)
virtual void mimic(ViewController *source_view)
Configure the settings of this view controller to give, as much as possible, a similar view as that g...
Ogre::Camera * getCamera() const
void setStatus(const QString &message)
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
virtual Ogre::Vector3 getVector() const
virtual void update(float dt, float ros_dt)
Called at 30Hz by ViewManager::update() while this view is active. Override with code that needs to r...
FloatProperty * yaw_property_
The camera's yaw (rotation around the y-axis), in radians.
virtual void onInitialize()
Do subclass-specific initialization. Called by ViewController::initialize after context_, target_scene_node_, and camera_ are set. This version calls updateTargetSceneNode().
static const float PITCH_LIMIT_HIGH
void hide()
Hide this Property in any PropertyTreeWidgets.
static const float PITCH_LIMIT_LOW
DisplayContext * context_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION