An orbital camera, controlled by yaw, pitch, distance, and focal point. More...
#include <orbit_view_controller.h>
Public Member Functions | |
virtual void | handleMouseEvent (ViewportMouseEvent &evt) |
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 to the fixed frame). | |
virtual void | mimic (ViewController *source_view) |
Configure the settings of this view controller to give, as much as possible, a similar view as that given by the source_view. | |
void | move (float x, float y, float z) |
virtual void | onInitialize () |
Do subclass-specific initialization. Called by ViewController::initialize after context_, target_scene_node_, and camera_ are set. | |
OrbitViewController () | |
void | pitch (float angle) |
virtual void | reset () |
void | yaw (float angle) |
void | zoom (float amount) |
Move in/out from the focal point, ie. adjust #distance_ by amount. | |
virtual | ~OrbitViewController () |
Protected Member Functions | |
void | calculatePitchYawFromPosition (const Ogre::Vector3 &position) |
Calculates pitch and yaw values given a new position and the current focal point. | |
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. | |
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 run repeatedly. | |
virtual void | updateCamera () |
Protected Attributes | |
FloatProperty * | distance_property_ |
The camera's distance from the focal point. | |
bool | dragging_ |
VectorProperty * | focal_point_property_ |
The point around which the camera "orbits". | |
Shape * | focal_shape_ |
FloatProperty * | pitch_property_ |
The camera's pitch (rotation around the x-axis), in radians. | |
FloatProperty * | yaw_property_ |
The camera's yaw (rotation around the y-axis), in radians. |
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 60 of file orbit_view_controller.h.
Definition at line 58 of file orbit_view_controller.cpp.
rviz::OrbitViewController::~OrbitViewController | ( | ) | [virtual] |
Definition at line 85 of file orbit_view_controller.cpp.
void rviz::OrbitViewController::calculatePitchYawFromPosition | ( | const Ogre::Vector3 & | position | ) | [protected] |
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 277 of file orbit_view_controller.cpp.
void rviz::OrbitViewController::handleMouseEvent | ( | ViewportMouseEvent & | evt | ) | [virtual] |
Reimplemented from rviz::ViewController.
Reimplemented in rviz::ThirdPersonFollowerViewController, and rviz::XYOrbitViewController.
Definition at line 99 of file orbit_view_controller.cpp.
void rviz::OrbitViewController::lookAt | ( | const Ogre::Vector3 & | point | ) | [virtual] |
This should be implemented in each subclass to aim the camera at the given point in space (relative to the fixed frame).
Reimplemented from rviz::ViewController.
Reimplemented in rviz::ThirdPersonFollowerViewController, and rviz::XYOrbitViewController.
Definition at line 232 of file orbit_view_controller.cpp.
void rviz::OrbitViewController::mimic | ( | ViewController * | source_view | ) | [virtual] |
Configure the settings of this view controller to give, as much as possible, a similar view as that given by the source_view.
source_view must return a valid Ogre::Camera*
from getCamera().
Reimplemented from rviz::FramePositionTrackingViewController.
Reimplemented in rviz::ThirdPersonFollowerViewController, and rviz::XYOrbitViewController.
Definition at line 200 of file orbit_view_controller.cpp.
void rviz::OrbitViewController::move | ( | float | x, |
float | y, | ||
float | z | ||
) |
Definition at line 289 of file orbit_view_controller.cpp.
void rviz::OrbitViewController::onInitialize | ( | ) | [virtual] |
Do subclass-specific initialization. Called by ViewController::initialize after context_, target_scene_node_, and camera_ are set.
Reimplemented from rviz::FramePositionTrackingViewController.
Reimplemented in rviz::ThirdPersonFollowerViewController, and rviz::XYOrbitViewController.
Definition at line 73 of file orbit_view_controller.cpp.
void rviz::OrbitViewController::onTargetFrameChanged | ( | const Ogre::Vector3 & | old_reference_position, |
const Ogre::Quaternion & | old_reference_orientation | ||
) | [protected, virtual] |
Override to implement the change in properties which nullifies the change in target frame.
Reimplemented from rviz::FramePositionTrackingViewController.
Definition at line 241 of file orbit_view_controller.cpp.
void rviz::OrbitViewController::pitch | ( | float | angle | ) |
Definition at line 272 of file orbit_view_controller.cpp.
void rviz::OrbitViewController::reset | ( | ) | [virtual] |
Reset the view controller to some sane initial state, like looking at 0,0,0 from a few meters away.
Implements rviz::ViewController.
Definition at line 90 of file orbit_view_controller.cpp.
void rviz::OrbitViewController::update | ( | float | dt, |
float | ros_dt | ||
) | [protected, virtual] |
Called at 30Hz by ViewManager::update() while this view is active. Override with code that needs to run repeatedly.
Reimplemented from rviz::FramePositionTrackingViewController.
Definition at line 226 of file orbit_view_controller.cpp.
void rviz::OrbitViewController::updateCamera | ( | ) | [protected, virtual] |
Reimplemented in rviz::ThirdPersonFollowerViewController, and rviz::XYOrbitViewController.
Definition at line 246 of file orbit_view_controller.cpp.
void rviz::OrbitViewController::yaw | ( | float | angle | ) |
Definition at line 267 of file orbit_view_controller.cpp.
void rviz::OrbitViewController::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 284 of file orbit_view_controller.cpp.
The camera's distance from the focal point.
Definition at line 108 of file orbit_view_controller.h.
bool rviz::OrbitViewController::dragging_ [protected] |
Definition at line 112 of file orbit_view_controller.h.
The point around which the camera "orbits".
Definition at line 109 of file orbit_view_controller.h.
Shape* rviz::OrbitViewController::focal_shape_ [protected] |
Definition at line 111 of file orbit_view_controller.h.
FloatProperty* rviz::OrbitViewController::pitch_property_ [protected] |
The camera's pitch (rotation around the x-axis), in radians.
Definition at line 107 of file orbit_view_controller.h.
FloatProperty* rviz::OrbitViewController::yaw_property_ [protected] |
The camera's yaw (rotation around the y-axis), in radians.
Definition at line 106 of file orbit_view_controller.h.