An un-constrained "flying" camera, specified by an eye point, focus point, and up vector. More...
#include <rviz_animated_view_controller.h>
Public Types | |
enum | { TRANSITION_LINEAR = 0, TRANSITION_SPHERICAL } |
Public Member Functions | |
AnimatedViewController () | |
virtual void | handleMouseEvent (rviz::ViewportMouseEvent &evt) |
virtual void | lookAt (const Ogre::Vector3 &point) |
Calls beginNewTransition() to move the focus point to the point provided, assumed to be in the Rviz 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_eye (float x, float y, float z) |
Applies a translation to only the eye point. | |
void | move_focus_and_eye (float x, float y, float z) |
Applies a translation to the focus and eye points. | |
void | moveEyeWithFocusTo (const Ogre::Vector3 &point) |
Calls beginNewTransition() to move the eye to the point given, keeping the direction fixed. | |
virtual void | onActivate () |
called by activate(). | |
virtual void | onInitialize () |
Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ are set. | |
void | orbitCameraTo (const Ogre::Vector3 &point) |
Calls beginNewTransition() with the focus point fixed, moving the eye to the point given. | |
virtual void | reset () |
Resets the camera parameters to a sane value. | |
virtual void | transitionFrom (ViewController *previous_view) |
Called by ViewManager when this ViewController is being made current. | |
void | yaw_pitch_roll (float yaw, float pitch, float roll) |
Applies a body-fixed-axes sequence of rotations; only accurate for small angles. | |
virtual | ~AnimatedViewController () |
Protected Slots | |
virtual void | onDistancePropertyChanged () |
Called when distance property is changed; computes new eye position. | |
virtual void | onEyePropertyChanged () |
Called when eye property is changed; computes new distance. | |
virtual void | onFocusPropertyChanged () |
Called focus property is changed; computes new distance. | |
virtual void | onUpPropertyChanged () |
Called when up vector property is changed (does nothing for now...). | |
virtual void | updateAttachedFrame () |
Called when Target Frame property changes while view is active. Purpose is to change values in the view controller (like a position offset) such that the actual viewpoint does not change. Calls updateTargetSceneNode() and onTargetFrameChanged(). | |
void | updateTopics () |
Protected Member Functions | |
Ogre::Vector3 | attachedLocalToFixedFrame (const Ogre::Vector3 &v) |
void | beginNewTransition (const Ogre::Vector3 &eye, const Ogre::Vector3 &focus, const Ogre::Vector3 &up, const ros::Duration &transition_time) |
Begins a camera movement animation to the given goal points. | |
void | cameraPlacementCallback (const view_controller_msgs::CameraPlacementConstPtr &cp_ptr) |
void | cancelTransition () |
Cancels any currently active camera movement. | |
void | connectPositionProperties () |
Convenience function; connects the signals/slots for position properties. | |
void | disconnectPositionProperties () |
Convenience function; disconnects the signals/slots for position properties. | |
Ogre::Vector3 | fixedFrameToAttachedLocal (const Ogre::Vector3 &v) |
float | getDistanceFromCameraToFocalPoint () |
Return the distance between camera and focal point. | |
Ogre::Quaternion | getOrientation () |
Return a Quaternion. | |
virtual void | onAttachedFrameChanged (const Ogre::Vector3 &old_reference_position, const Ogre::Quaternion &old_reference_orientation) |
Override to implement the change in properties which nullifies the change in attached frame. | |
void | setPropertiesFromCamera (Ogre::Camera *source_camera) |
void | transformCameraPlacementToAttachedFrame (view_controller_msgs::CameraPlacement &cp) |
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. | |
void | updateAttachedSceneNode () |
Update the position of the attached_scene_node_ from the TF frame specified in the Attached Frame property. | |
void | updateCamera () |
Updates the Ogre camera properties from the view controller properties. | |
Protected Attributes | |
bool | animate_ |
rviz::TfFrameProperty * | attached_frame_property_ |
Ogre::SceneNode * | attached_scene_node_ |
rviz::RosTopicProperty * | camera_placement_topic_property_ |
ros::Duration | current_transition_duration_ |
rviz::FloatProperty * | default_transition_time_property_ |
A default time for any animation requests. | |
rviz::FloatProperty * | distance_property_ |
The camera's distance from the focal point. | |
bool | dragging_ |
A flag indicating the dragging state of the mouse. | |
rviz::VectorProperty * | eye_point_property_ |
The position of the camera. | |
rviz::BoolProperty * | fixed_up_property_ |
If True, "up" is fixed to ... up. | |
rviz::Shape * | focal_shape_ |
A small ellipsoid to show the focus point. | |
rviz::VectorProperty * | focus_point_property_ |
The point around which the camera "orbits". | |
Ogre::Vector3 | goal_focus_ |
Ogre::Vector3 | goal_position_ |
Ogre::Vector3 | goal_up_ |
QCursor | interaction_disabled_cursor_ |
A cursor for indicating mouse interaction is disabled. | |
rviz::EditableEnumProperty * | interaction_mode_property_ |
Select between Orbit or FPS control style. | |
rviz::BoolProperty * | mouse_enabled_property_ |
If True, most user changes to camera state are disabled. | |
ros::NodeHandle | nh_ |
ros::Subscriber | placement_subscriber_ |
Ogre::Quaternion | reference_orientation_ |
Used to store the orientation of the attached frame relative to <Fixed frame>=""> | |
Ogre::Vector3 | reference_position_ |
Used to store the position of the attached frame relative to <Fixed frame>=""> | |
Ogre::Vector3 | start_focus_ |
Ogre::Vector3 | start_position_ |
Ogre::Vector3 | start_up_ |
ros::Time | trajectory_start_time_ |
ros::Time | transition_start_time_ |
rviz::VectorProperty * | up_vector_property_ |
The up vector for the camera. |
An un-constrained "flying" camera, specified by an eye point, focus point, and up vector.
Definition at line 61 of file rviz_animated_view_controller.h.
anonymous enum |
Definition at line 66 of file rviz_animated_view_controller.h.
Definition at line 94 of file rviz_animated_view_controller.cpp.
Definition at line 138 of file rviz_animated_view_controller.cpp.
Ogre::Vector3 rviz_animated_view_controller::AnimatedViewController::attachedLocalToFixedFrame | ( | const Ogre::Vector3 & | v | ) | [inline, protected] |
Definition at line 190 of file rviz_animated_view_controller.h.
void rviz_animated_view_controller::AnimatedViewController::beginNewTransition | ( | const Ogre::Vector3 & | eye, |
const Ogre::Vector3 & | focus, | ||
const Ogre::Vector3 & | up, | ||
const ros::Duration & | transition_time | ||
) | [protected] |
Begins a camera movement animation to the given goal points.
Definition at line 506 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::cameraPlacementCallback | ( | const view_controller_msgs::CameraPlacementConstPtr & | cp_ptr | ) | [protected] |
Definition at line 540 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::cancelTransition | ( | ) | [protected] |
Cancels any currently active camera movement.
Definition at line 535 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::connectPositionProperties | ( | ) | [protected] |
Convenience function; connects the signals/slots for position properties.
Definition at line 189 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::disconnectPositionProperties | ( | ) | [protected] |
Convenience function; disconnects the signals/slots for position properties.
Definition at line 197 of file rviz_animated_view_controller.cpp.
Ogre::Vector3 rviz_animated_view_controller::AnimatedViewController::fixedFrameToAttachedLocal | ( | const Ogre::Vector3 & | v | ) | [inline, protected] |
Definition at line 189 of file rviz_animated_view_controller.h.
float rviz_animated_view_controller::AnimatedViewController::getDistanceFromCameraToFocalPoint | ( | ) | [protected] |
Return the distance between camera and focal point.
Definition at line 288 of file rviz_animated_view_controller.cpp.
Ogre::Quaternion rviz_animated_view_controller::AnimatedViewController::getOrientation | ( | ) | [protected] |
Return a Quaternion.
Definition at line 757 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::handleMouseEvent | ( | rviz::ViewportMouseEvent & | evt | ) | [virtual] |
Reimplemented from rviz::ViewController.
Definition at line 312 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::lookAt | ( | const Ogre::Vector3 & | point | ) | [virtual] |
Calls beginNewTransition() to move the focus point to the point provided, assumed to be in the Rviz Fixed Frame.
Reimplemented from rviz::ViewController.
Definition at line 640 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::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::ViewController.
Definition at line 461 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::move_eye | ( | float | x, |
float | y, | ||
float | z | ||
) |
Applies a translation to only the eye point.
Definition at line 769 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::move_focus_and_eye | ( | float | x, |
float | y, | ||
float | z | ||
) |
Applies a translation to the focus and eye points.
Definition at line 762 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::moveEyeWithFocusTo | ( | const Ogre::Vector3 & | point | ) |
Calls beginNewTransition() to move the eye to the point given, keeping the direction fixed.
Definition at line 662 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::onActivate | ( | ) | [virtual] |
called by activate().
This version calls updateAttachedSceneNode().
Reimplemented from rviz::ViewController.
Definition at line 170 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::onAttachedFrameChanged | ( | 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 attached frame.
Definition at line 268 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::onDistancePropertyChanged | ( | ) | [protected, virtual, slot] |
Called when distance property is changed; computes new eye position.
Definition at line 215 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::onEyePropertyChanged | ( | ) | [protected, virtual, slot] |
Called when eye property is changed; computes new distance.
Definition at line 205 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::onFocusPropertyChanged | ( | ) | [protected, virtual, slot] |
Called focus property is changed; computes new distance.
Definition at line 210 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::onInitialize | ( | ) | [virtual] |
Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ are set.
This version sets up the attached_scene_node, focus shape, and subscribers.
Reimplemented from rviz::ViewController.
Definition at line 154 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::onUpPropertyChanged | ( | ) | [protected, virtual, slot] |
Called when up vector property is changed (does nothing for now...).
Definition at line 223 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::orbitCameraTo | ( | const Ogre::Vector3 & | point | ) |
Calls beginNewTransition() with the focus point fixed, moving the eye to the point given.
Definition at line 655 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::reset | ( | ) | [virtual] |
Resets the camera parameters to a sane value.
Implements rviz::ViewController.
Definition at line 293 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::setPropertiesFromCamera | ( | Ogre::Camera * | source_camera | ) | [protected] |
Definition at line 446 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::transformCameraPlacementToAttachedFrame | ( | view_controller_msgs::CameraPlacement & | cp | ) | [protected] |
Definition at line 611 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::transitionFrom | ( | ViewController * | previous_view | ) | [virtual] |
Called by ViewManager when this ViewController is being made current.
previous_view | is the previous "current" view, and will not be NULL. |
This gives ViewController subclasses an opportunity to implement a smooth transition from a previous viewpoint to the new viewpoint.
Reimplemented from rviz::ViewController.
Definition at line 489 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::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::ViewController.
Definition at line 670 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::updateAttachedFrame | ( | ) | [protected, virtual, slot] |
Called when Target Frame property changes while view is active. Purpose is to change values in the view controller (like a position offset) such that the actual viewpoint does not change. Calls updateTargetSceneNode() and onTargetFrameChanged().
Definition at line 240 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::updateAttachedSceneNode | ( | ) | [protected] |
Update the position of the attached_scene_node_ from the TF frame specified in the Attached Frame property.
Definition at line 250 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::updateCamera | ( | ) | [protected] |
Updates the Ogre camera properties from the view controller properties.
Definition at line 706 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::updateTopics | ( | ) | [protected, slot] |
Definition at line 144 of file rviz_animated_view_controller.cpp.
void rviz_animated_view_controller::AnimatedViewController::yaw_pitch_roll | ( | float | yaw, |
float | pitch, | ||
float | roll | ||
) |
Applies a body-fixed-axes sequence of rotations; only accurate for small angles.
Definition at line 715 of file rviz_animated_view_controller.cpp.
bool rviz_animated_view_controller::AnimatedViewController::animate_ [protected] |
Definition at line 224 of file rviz_animated_view_controller.h.
rviz::TfFrameProperty* rviz_animated_view_controller::AnimatedViewController::attached_frame_property_ [protected] |
Definition at line 217 of file rviz_animated_view_controller.h.
Ogre::SceneNode* rviz_animated_view_controller::AnimatedViewController::attached_scene_node_ [protected] |
Definition at line 218 of file rviz_animated_view_controller.h.
rviz::RosTopicProperty* rviz_animated_view_controller::AnimatedViewController::camera_placement_topic_property_ [protected] |
Definition at line 214 of file rviz_animated_view_controller.h.
ros::Duration rviz_animated_view_controller::AnimatedViewController::current_transition_duration_ [protected] |
Definition at line 230 of file rviz_animated_view_controller.h.
rviz::FloatProperty* rviz_animated_view_controller::AnimatedViewController::default_transition_time_property_ [protected] |
A default time for any animation requests.
Definition at line 212 of file rviz_animated_view_controller.h.
rviz::FloatProperty* rviz_animated_view_controller::AnimatedViewController::distance_property_ [protected] |
The camera's distance from the focal point.
Definition at line 208 of file rviz_animated_view_controller.h.
bool rviz_animated_view_controller::AnimatedViewController::dragging_ [protected] |
A flag indicating the dragging state of the mouse.
Definition at line 233 of file rviz_animated_view_controller.h.
rviz::VectorProperty* rviz_animated_view_controller::AnimatedViewController::eye_point_property_ [protected] |
The position of the camera.
Definition at line 209 of file rviz_animated_view_controller.h.
rviz::BoolProperty* rviz_animated_view_controller::AnimatedViewController::fixed_up_property_ [protected] |
If True, "up" is fixed to ... up.
Definition at line 206 of file rviz_animated_view_controller.h.
A small ellipsoid to show the focus point.
Definition at line 232 of file rviz_animated_view_controller.h.
rviz::VectorProperty* rviz_animated_view_controller::AnimatedViewController::focus_point_property_ [protected] |
The point around which the camera "orbits".
Definition at line 210 of file rviz_animated_view_controller.h.
Ogre::Vector3 rviz_animated_view_controller::AnimatedViewController::goal_focus_ [protected] |
Definition at line 226 of file rviz_animated_view_controller.h.
Ogre::Vector3 rviz_animated_view_controller::AnimatedViewController::goal_position_ [protected] |
Definition at line 225 of file rviz_animated_view_controller.h.
Ogre::Vector3 rviz_animated_view_controller::AnimatedViewController::goal_up_ [protected] |
Definition at line 227 of file rviz_animated_view_controller.h.
QCursor rviz_animated_view_controller::AnimatedViewController::interaction_disabled_cursor_ [protected] |
A cursor for indicating mouse interaction is disabled.
Definition at line 235 of file rviz_animated_view_controller.h.
rviz::EditableEnumProperty* rviz_animated_view_controller::AnimatedViewController::interaction_mode_property_ [protected] |
Select between Orbit or FPS control style.
Definition at line 205 of file rviz_animated_view_controller.h.
rviz::BoolProperty* rviz_animated_view_controller::AnimatedViewController::mouse_enabled_property_ [protected] |
If True, most user changes to camera state are disabled.
Definition at line 204 of file rviz_animated_view_controller.h.
Definition at line 202 of file rviz_animated_view_controller.h.
ros::Subscriber rviz_animated_view_controller::AnimatedViewController::placement_subscriber_ [protected] |
Definition at line 238 of file rviz_animated_view_controller.h.
Ogre::Quaternion rviz_animated_view_controller::AnimatedViewController::reference_orientation_ [protected] |
Used to store the orientation of the attached frame relative to <Fixed frame>="">
Definition at line 220 of file rviz_animated_view_controller.h.
Ogre::Vector3 rviz_animated_view_controller::AnimatedViewController::reference_position_ [protected] |
Used to store the position of the attached frame relative to <Fixed frame>="">
Definition at line 221 of file rviz_animated_view_controller.h.
Ogre::Vector3 rviz_animated_view_controller::AnimatedViewController::start_focus_ [protected] |
Definition at line 226 of file rviz_animated_view_controller.h.
Ogre::Vector3 rviz_animated_view_controller::AnimatedViewController::start_position_ [protected] |
Definition at line 225 of file rviz_animated_view_controller.h.
Ogre::Vector3 rviz_animated_view_controller::AnimatedViewController::start_up_ [protected] |
Definition at line 227 of file rviz_animated_view_controller.h.
Definition at line 228 of file rviz_animated_view_controller.h.
Definition at line 229 of file rviz_animated_view_controller.h.
rviz::VectorProperty* rviz_animated_view_controller::AnimatedViewController::up_vector_property_ [protected] |
The up vector for the camera.
Definition at line 211 of file rviz_animated_view_controller.h.