Public Member Functions | Private Member Functions | Private Attributes | List of all members
rviz::OrbitCamera Class Reference

An orbital camera, controlled by yaw, pitch, distance, and focal point. More...

#include <orbit_camera.h>

Inheritance diagram for rviz::OrbitCamera:
Inheritance graph
[legend]

Public Member Functions

void fromString (const std::string &str) override
 Loads the camera's configure from the supplied string (generated through toString()) More...
 
float getDistance ()
 
const Ogre::Vector3 & getFocalPoint ()
 
Ogre::Quaternion getOrientation () override
 Get the orientation of this camera. More...
 
float getPitch ()
 
Ogre::Vector3 getPosition () override
 Get the position of this camera. More...
 
float getYaw ()
 
void lookAt (const Ogre::Vector3 &point) override
 Point the camera at the specified point. More...
 
void mouseLeftDown (int x, int y) override
 
void mouseLeftDrag (int diff_x, int diff_y, bool ctrl, bool alt, bool shift) override
 Handle a left mouse button drag. More...
 
void mouseLeftUp (int x, int y) override
 
void mouseMiddleDown (int x, int y) override
 
void mouseMiddleDrag (int diff_x, int diff_y, bool ctrl, bool alt, bool shift) override
 Handle a middle mouse button drag. More...
 
void mouseMiddleUp (int x, int y) override
 
void mouseRightDown (int x, int y) override
 
void mouseRightDrag (int diff_x, int diff_y, bool ctrl, bool alt, bool shift) override
 Handle a right mouse button drag. More...
 
void mouseRightUp (int x, int y) override
 
void move (float x, float y, float z) override
 Move the camera relative to its orientation. More...
 
 OrbitCamera (Ogre::SceneManager *scene_manager)
 
void pitch (float angle) override
 Pitch the camera. More...
 
void roll (float angle) override
 Roll the camera. More...
 
void scrollWheel (int diff, bool ctrl, bool alt, bool shift) override
 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...
 
void setFrom (CameraBase *camera) override
 Set the position/orientation of this camera from another camera. More...
 
void setOrientation (float x, float y, float z, float w) override
 Set the orientation of the camera from a quaternion. More...
 
void setPosition (float x, float y, float z) override
 Set the position of the camera. More...
 
std::string toString () override
 Returns a string representation of the camera's configuration. More...
 
void update () override
 Calculates the camera's position and orientation from the yaw, pitch, distance and focal point. More...
 
void yaw (float angle) override
 Yaw the camera. More...
 
void zoom (float amount)
 Move in/out from the focal point, ie. adjust distance_ by amount. More...
 
 ~OrbitCamera () override
 
- 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...
 
Shapefocal_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...
 

Detailed Description

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 61 of file orbit_camera.h.

Constructor & Destructor Documentation

◆ OrbitCamera()

rviz::OrbitCamera::OrbitCamera ( Ogre::SceneManager *  scene_manager)

Definition at line 52 of file orbit_camera.cpp.

◆ ~OrbitCamera()

rviz::OrbitCamera::~OrbitCamera ( )
override

Definition at line 67 of file orbit_camera.cpp.

Member Function Documentation

◆ calculatePitchYawFromPosition()

void rviz::OrbitCamera::calculatePitchYawFromPosition ( const Ogre::Vector3 &  position)
private

Calculates pitch and yaw values given a new position and the current focal point.

Parameters
positionPosition to calculate the pitch/yaw for

Definition at line 162 of file orbit_camera.cpp.

◆ fromString()

void rviz::OrbitCamera::fromString ( const std::string &  str)
overridevirtual

Loads the camera's configure from the supplied string (generated through toString())

Parameters
strThe string to load from

Implements rviz::CameraBase.

Definition at line 343 of file orbit_camera.cpp.

◆ getDistance()

float rviz::OrbitCamera::getDistance ( )
inline

Definition at line 87 of file orbit_camera.h.

◆ getFocalPoint()

const Ogre::Vector3& rviz::OrbitCamera::getFocalPoint ( )
inline

Definition at line 91 of file orbit_camera.h.

◆ getGlobalFocalPoint()

Ogre::Vector3 rviz::OrbitCamera::getGlobalFocalPoint ( )
private

Definition at line 94 of file orbit_camera.cpp.

◆ getOrientation()

Ogre::Quaternion rviz::OrbitCamera::getOrientation ( )
overridevirtual

Get the orientation of this camera.

Returns
The orientation of this camera

Implements rviz::CameraBase.

Definition at line 157 of file orbit_camera.cpp.

◆ getPitch()

float rviz::OrbitCamera::getPitch ( )
inline

Definition at line 79 of file orbit_camera.h.

◆ getPosition()

Ogre::Vector3 rviz::OrbitCamera::getPosition ( )
overridevirtual

Get the position of this camera.

Returns
The position of this camera

Implements rviz::CameraBase.

Definition at line 152 of file orbit_camera.cpp.

◆ getYaw()

float rviz::OrbitCamera::getYaw ( )
inline

Definition at line 83 of file orbit_camera.h.

◆ lookAt()

void rviz::OrbitCamera::lookAt ( const Ogre::Vector3 &  point)
overridevirtual

Point the camera at the specified point.

Parameters
pointThe point to look at

Implements rviz::CameraBase.

Definition at line 251 of file orbit_camera.cpp.

◆ mouseLeftDown()

void rviz::OrbitCamera::mouseLeftDown ( int  x,
int  y 
)
overridevirtual

Reimplemented from rviz::CameraBase.

Definition at line 313 of file orbit_camera.cpp.

◆ mouseLeftDrag()

void rviz::OrbitCamera::mouseLeftDrag ( int  diff_x,
int  diff_y,
bool  ctrl,
bool  alt,
bool  shift 
)
overridevirtual

Handle a left mouse button drag.

Parameters
diff_xPixels the mouse has moved in the (window space) x direction
diff_yPixels the mouse has moved in the (window space) y direction

Implements rviz::CameraBase.

Definition at line 271 of file orbit_camera.cpp.

◆ mouseLeftUp()

void rviz::OrbitCamera::mouseLeftUp ( int  x,
int  y 
)
overridevirtual

Reimplemented from rviz::CameraBase.

Definition at line 328 of file orbit_camera.cpp.

◆ mouseMiddleDown()

void rviz::OrbitCamera::mouseMiddleDown ( int  x,
int  y 
)
overridevirtual

Reimplemented from rviz::CameraBase.

Definition at line 318 of file orbit_camera.cpp.

◆ mouseMiddleDrag()

void rviz::OrbitCamera::mouseMiddleDrag ( int  diff_x,
int  diff_y,
bool  ctrl,
bool  alt,
bool  shift 
)
overridevirtual

Handle a middle mouse button drag.

Parameters
diff_xPixels the mouse has moved in the (window space) x direction
diff_yPixels the mouse has moved in the (window space) y direction

Implements rviz::CameraBase.

Definition at line 277 of file orbit_camera.cpp.

◆ mouseMiddleUp()

void rviz::OrbitCamera::mouseMiddleUp ( int  x,
int  y 
)
overridevirtual

Reimplemented from rviz::CameraBase.

Definition at line 333 of file orbit_camera.cpp.

◆ mouseRightDown()

void rviz::OrbitCamera::mouseRightDown ( int  x,
int  y 
)
overridevirtual

Reimplemented from rviz::CameraBase.

Definition at line 323 of file orbit_camera.cpp.

◆ mouseRightDrag()

void rviz::OrbitCamera::mouseRightDrag ( int  diff_x,
int  diff_y,
bool  ctrl,
bool  alt,
bool  shift 
)
overridevirtual

Handle a right mouse button drag.

Parameters
diff_xPixels the mouse has moved in the (window space) x direction
diff_yPixels the mouse has moved in the (window space) y direction

Implements rviz::CameraBase.

Definition at line 289 of file orbit_camera.cpp.

◆ mouseRightUp()

void rviz::OrbitCamera::mouseRightUp ( int  x,
int  y 
)
overridevirtual

Reimplemented from rviz::CameraBase.

Definition at line 338 of file orbit_camera.cpp.

◆ move()

void rviz::OrbitCamera::move ( float  x,
float  y,
float  z 
)
overridevirtual

Move the camera relative to its orientation.

Parameters
xDistance to move along the X-axis
yDistance to move along the Y-axis
zDistance to move along the Z-axis

Implements rviz::CameraBase.

Definition at line 227 of file orbit_camera.cpp.

◆ normalizePitch()

void rviz::OrbitCamera::normalizePitch ( )
private

Normalizes the camera's pitch, preventing it from reaching vertical (or turning upside down)

Definition at line 72 of file orbit_camera.cpp.

◆ normalizeYaw()

void rviz::OrbitCamera::normalizeYaw ( )
private

Normalizes the camera's yaw in the range [0, 2*pi)

Definition at line 84 of file orbit_camera.cpp.

◆ pitch()

void rviz::OrbitCamera::pitch ( float  angle)
overridevirtual

Pitch the camera.

Calls to pitch are cumulative, so: pitch(PI); pitch(PI);

is equivalent to pitch(2*PI);

Parameters
angleAngle to pitch, in radians

Implements rviz::CameraBase.

Definition at line 139 of file orbit_camera.cpp.

◆ roll()

void rviz::OrbitCamera::roll ( float  angle)
overridevirtual

Roll the camera.

Calls to roll are cumulative, so: roll(PI); roll(PI);

is equivalent to roll(2*PI);

Parameters
angleAngle to roll, in radians

Implements rviz::CameraBase.

Definition at line 148 of file orbit_camera.cpp.

◆ scrollWheel()

void rviz::OrbitCamera::scrollWheel ( int  diff,
bool  ctrl,
bool  alt,
bool  shift 
)
overridevirtual

Handle a scrollwheel change.

Parameters
diffNumber of "units" the scrollwheel has moved
Todo:
Probably need to pass in how many units there are in a "click" of the wheel

Implements rviz::CameraBase.

Definition at line 301 of file orbit_camera.cpp.

◆ setFocalPoint()

void rviz::OrbitCamera::setFocalPoint ( const Ogre::Vector3 &  focal_point)

Set the focal point of the camera. Keeps the pitch/yaw/distance the same.

Parameters
focal_pointThe new focal point

Definition at line 220 of file orbit_camera.cpp.

◆ setFrom()

void rviz::OrbitCamera::setFrom ( CameraBase camera)
overridevirtual

Set the position/orientation of this camera from another camera.

Parameters
cameraThe camera to set from

Implements rviz::CameraBase.

Definition at line 182 of file orbit_camera.cpp.

◆ setOrientation()

void rviz::OrbitCamera::setOrientation ( float  x,
float  y,
float  z,
float  w 
)
overridevirtual

Set the orientation of the camera from a quaternion.

Implements rviz::CameraBase.

Definition at line 195 of file orbit_camera.cpp.

◆ setPosition()

void rviz::OrbitCamera::setPosition ( float  x,
float  y,
float  z 
)
overridevirtual

Set the position of the camera.

Implements rviz::CameraBase.

Definition at line 241 of file orbit_camera.cpp.

◆ toString()

std::string rviz::OrbitCamera::toString ( )
overridevirtual

Returns a string representation of the camera's configuration.

Implements rviz::CameraBase.

Definition at line 362 of file orbit_camera.cpp.

◆ update()

void rviz::OrbitCamera::update ( )
overridevirtual

Calculates the camera's position and orientation from the yaw, pitch, distance and focal point.

Implements rviz::CameraBase.

Definition at line 106 of file orbit_camera.cpp.

◆ yaw()

void rviz::OrbitCamera::yaw ( float  angle)
overridevirtual

Yaw the camera.

Calls to yaw are cumulative, so: yaw(PI); yaw(PI);

is equivalent to yaw(2*PI);

Parameters
angleAngle to yaw, in radians

Implements rviz::CameraBase.

Definition at line 130 of file orbit_camera.cpp.

◆ zoom()

void rviz::OrbitCamera::zoom ( float  amount)

Move in/out from the focal point, ie. adjust distance_ by amount.

Parameters
amountThe distance to move. Positive amount moves towards the focal point, negative moves away

Definition at line 208 of file orbit_camera.cpp.

Member Data Documentation

◆ distance_

float rviz::OrbitCamera::distance_
private

The camera's distance from the focal point.

Definition at line 150 of file orbit_camera.h.

◆ focal_point_

Ogre::Vector3 rviz::OrbitCamera::focal_point_
private

The camera's focal point.

Definition at line 147 of file orbit_camera.h.

◆ focal_point_object_

Shape* rviz::OrbitCamera::focal_point_object_
private

Definition at line 152 of file orbit_camera.h.

◆ pitch_

float rviz::OrbitCamera::pitch_
private

The camera's pitch (rotation around the x-axis), in radians.

Definition at line 149 of file orbit_camera.h.

◆ yaw_

float rviz::OrbitCamera::yaw_
private

The camera's yaw (rotation around the y-axis), in radians.

Definition at line 148 of file orbit_camera.h.


The documentation for this class was generated from the following files:


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