An orbital camera, controlled by yaw, pitch, distance, and focal point. More...
#include <orbit_camera.h>
Public Member Functions | |
virtual void | fromString (const std::string &str) |
Loads the camera's configure from the supplied string (generated through toString()) More... | |
float | getDistance () |
const Ogre::Vector3 & | getFocalPoint () |
virtual Ogre::Quaternion | getOrientation () |
Get the orientation of this camera. More... | |
float | getPitch () |
virtual Ogre::Vector3 | getPosition () |
Get the position of this camera. More... | |
float | getYaw () |
virtual void | lookAt (const Ogre::Vector3 &point) |
Point the camera at the specified point. More... | |
virtual void | mouseLeftDown (int x, int y) |
virtual void | mouseLeftDrag (int diff_x, int diff_y, bool ctrl, bool alt, bool shift) |
Handle a left mouse button drag. More... | |
virtual void | mouseLeftUp (int x, int y) |
virtual void | mouseMiddleDown (int x, int y) |
virtual void | mouseMiddleDrag (int diff_x, int diff_y, bool ctrl, bool alt, bool shift) |
Handle a middle mouse button drag. More... | |
virtual void | mouseMiddleUp (int x, int y) |
virtual void | mouseRightDown (int x, int y) |
virtual void | mouseRightDrag (int diff_x, int diff_y, bool ctrl, bool alt, bool shift) |
Handle a right mouse button drag. More... | |
virtual void | mouseRightUp (int x, int y) |
virtual void | move (float x, float y, float z) |
Move the camera relative to its orientation. More... | |
OrbitCamera (Ogre::SceneManager *scene_manager) | |
virtual void | pitch (float angle) |
Pitch the camera. More... | |
virtual void | roll (float angle) |
Roll the camera. More... | |
virtual void | scrollWheel (int diff, bool ctrl, bool alt, bool shift) |
Handle a scrollwheel change. More... | |
void | setFocalPoint (const Ogre::Vector3 &focal_point) |
Set the focal point of the camera. Keeps the pitch/yaw/distance the same. More... | |
virtual void | setFrom (CameraBase *camera) |
Set the position/orientation of this camera from another camera. More... | |
virtual void | setOrientation (float x, float y, float z, float w) |
Set the orientation of the camera from a quaternion. More... | |
virtual void | setPosition (float x, float y, float z) |
Set the position of the camera. More... | |
virtual std::string | toString () |
Returns a string representation of the camera's configuration. More... | |
virtual void | update () |
Calculates the camera's position and orientation from the yaw, pitch, distance and focal point. More... | |
virtual void | yaw (float angle) |
Yaw the camera. More... | |
void | zoom (float amount) |
Move in/out from the focal point, ie. adjust distance_ by amount. More... | |
virtual | ~OrbitCamera () |
Public Member Functions inherited from rviz::CameraBase | |
CameraBase (Ogre::SceneManager *scene_manager) | |
Constructor. More... | |
Ogre::Camera * | getOgreCamera () |
Get the Ogre camera associated with this camera object. More... | |
virtual void | relativeNodeChanged () |
Called when the relative node changes. More... | |
virtual void | setOrientation (const Ogre::Quaternion &orientation) |
Set the orientation of the camera. More... | |
virtual void | setPosition (const Ogre::Vector3 &position) |
Set the position of the camera. More... | |
void | setRelativeNode (Ogre::SceneNode *node) |
Set a scene node that all camera transformations should be relative to. More... | |
virtual | ~CameraBase () |
Private Member Functions | |
void | calculatePitchYawFromPosition (const Ogre::Vector3 &position) |
Calculates pitch and yaw values given a new position and the current focal point. More... | |
Ogre::Vector3 | getGlobalFocalPoint () |
void | normalizePitch () |
Normalizes the camera's pitch, preventing it from reaching vertical (or turning upside down) More... | |
void | normalizeYaw () |
Normalizes the camera's yaw in the range [0, 2*pi) More... | |
Private Attributes | |
float | distance_ |
The camera's distance from the focal point. More... | |
Ogre::Vector3 | focal_point_ |
The camera's focal point. More... | |
Shape * | focal_point_object_ |
float | pitch_ |
The camera's pitch (rotation around the x-axis), in radians. More... | |
float | yaw_ |
The camera's yaw (rotation around the y-axis), in radians. More... | |
Additional Inherited Members | |
Protected Attributes inherited from rviz::CameraBase | |
Ogre::Camera * | camera_ |
Ogre camera associated with this camera object. More... | |
Ogre::SceneNode * | relative_node_ |
Ogre::SceneManager * | scene_manager_ |
Scene manager this camera is part of. More... | |
An orbital camera, controlled by yaw, pitch, distance, and focal point.
This camera is based on the equation of a sphere in spherical coordinates:
x = d*cos(theta)sin(phi) y = d*cos(phi) z = d*sin(theta)sin(phi)
Where:
d = distance_
theta = yaw_
phi = pitch_
Definition at line 62 of file orbit_camera.h.
rviz::OrbitCamera::OrbitCamera | ( | Ogre::SceneManager * | scene_manager | ) |
Definition at line 53 of file orbit_camera.cpp.
|
virtual |
Definition at line 68 of file orbit_camera.cpp.
|
private |
Calculates pitch and yaw values given a new position and the current focal point.
position | Position to calculate the pitch/yaw for |
Definition at line 163 of file orbit_camera.cpp.
|
virtual |
Loads the camera's configure from the supplied string (generated through toString())
str | The string to load from |
Implements rviz::CameraBase.
Definition at line 344 of file orbit_camera.cpp.
|
inline |
Definition at line 81 of file orbit_camera.h.
|
inline |
Definition at line 82 of file orbit_camera.h.
|
private |
Definition at line 95 of file orbit_camera.cpp.
|
virtual |
Get the orientation of this camera.
Implements rviz::CameraBase.
Definition at line 158 of file orbit_camera.cpp.
|
inline |
Definition at line 79 of file orbit_camera.h.
|
virtual |
Get the position of this camera.
Implements rviz::CameraBase.
Definition at line 153 of file orbit_camera.cpp.
|
inline |
Definition at line 80 of file orbit_camera.h.
|
virtual |
Point the camera at the specified point.
point | The point to look at |
Implements rviz::CameraBase.
Definition at line 252 of file orbit_camera.cpp.
|
virtual |
Reimplemented from rviz::CameraBase.
Definition at line 314 of file orbit_camera.cpp.
|
virtual |
Handle a left mouse button drag.
diff_x | Pixels the mouse has moved in the (window space) x direction |
diff_y | Pixels the mouse has moved in the (window space) y direction |
Implements rviz::CameraBase.
Definition at line 272 of file orbit_camera.cpp.
|
virtual |
Reimplemented from rviz::CameraBase.
Definition at line 329 of file orbit_camera.cpp.
|
virtual |
Reimplemented from rviz::CameraBase.
Definition at line 319 of file orbit_camera.cpp.
|
virtual |
Handle a middle mouse button drag.
diff_x | Pixels the mouse has moved in the (window space) x direction |
diff_y | Pixels the mouse has moved in the (window space) y direction |
Implements rviz::CameraBase.
Definition at line 278 of file orbit_camera.cpp.
|
virtual |
Reimplemented from rviz::CameraBase.
Definition at line 334 of file orbit_camera.cpp.
|
virtual |
Reimplemented from rviz::CameraBase.
Definition at line 324 of file orbit_camera.cpp.
|
virtual |
Handle a right mouse button drag.
diff_x | Pixels the mouse has moved in the (window space) x direction |
diff_y | Pixels the mouse has moved in the (window space) y direction |
Implements rviz::CameraBase.
Definition at line 290 of file orbit_camera.cpp.
|
virtual |
Reimplemented from rviz::CameraBase.
Definition at line 339 of file orbit_camera.cpp.
|
virtual |
Move the camera relative to its orientation.
x | Distance to move along the X-axis |
y | Distance to move along the Y-axis |
z | Distance to move along the Z-axis |
Implements rviz::CameraBase.
Definition at line 228 of file orbit_camera.cpp.
|
private |
Normalizes the camera's pitch, preventing it from reaching vertical (or turning upside down)
Definition at line 73 of file orbit_camera.cpp.
|
private |
Normalizes the camera's yaw in the range [0, 2*pi)
Definition at line 85 of file orbit_camera.cpp.
|
virtual |
Pitch the camera.
Calls to pitch are cumulative, so: pitch(PI); pitch(PI);
is equivalent to pitch(2*PI);
angle | Angle to pitch, in radians |
Implements rviz::CameraBase.
Definition at line 140 of file orbit_camera.cpp.
|
virtual |
Roll the camera.
Calls to roll are cumulative, so: roll(PI); roll(PI);
is equivalent to roll(2*PI);
angle | Angle to roll, in radians |
Implements rviz::CameraBase.
Definition at line 149 of file orbit_camera.cpp.
|
virtual |
Handle a scrollwheel change.
diff | Number of "units" the scrollwheel has moved |
Implements rviz::CameraBase.
Definition at line 302 of file orbit_camera.cpp.
void rviz::OrbitCamera::setFocalPoint | ( | const Ogre::Vector3 & | focal_point | ) |
Set the focal point of the camera. Keeps the pitch/yaw/distance the same.
focal_point | The new focal point |
Definition at line 221 of file orbit_camera.cpp.
|
virtual |
Set the position/orientation of this camera from another camera.
camera | The camera to set from |
Implements rviz::CameraBase.
Definition at line 183 of file orbit_camera.cpp.
|
virtual |
Set the orientation of the camera from a quaternion.
Implements rviz::CameraBase.
Definition at line 196 of file orbit_camera.cpp.
|
virtual |
Set the position of the camera.
Implements rviz::CameraBase.
Definition at line 242 of file orbit_camera.cpp.
|
virtual |
Returns a string representation of the camera's configuration.
Implements rviz::CameraBase.
Definition at line 363 of file orbit_camera.cpp.
|
virtual |
Calculates the camera's position and orientation from the yaw, pitch, distance and focal point.
Implements rviz::CameraBase.
Definition at line 107 of file orbit_camera.cpp.
|
virtual |
Yaw the camera.
Calls to yaw are cumulative, so: yaw(PI); yaw(PI);
is equivalent to yaw(2*PI);
angle | Angle to yaw, in radians |
Implements rviz::CameraBase.
Definition at line 131 of file orbit_camera.cpp.
void rviz::OrbitCamera::zoom | ( | float | amount | ) |
Move in/out from the focal point, ie. adjust distance_ by amount.
amount | The distance to move. Positive amount moves towards the focal point, negative moves away |
Definition at line 209 of file orbit_camera.cpp.
|
private |
The camera's distance from the focal point.
Definition at line 138 of file orbit_camera.h.
|
private |
The camera's focal point.
Definition at line 135 of file orbit_camera.h.
|
private |
Definition at line 140 of file orbit_camera.h.
|
private |
The camera's pitch (rotation around the x-axis), in radians.
Definition at line 137 of file orbit_camera.h.
|
private |
The camera's yaw (rotation around the y-axis), in radians.
Definition at line 136 of file orbit_camera.h.