An un-constrained "flying" camera, specified by an eye point, focus point, and up vector. More...
#include <tablet_view_controller.h>
Public Types | |
enum | { TRANSITION_LINEAR = 0, TRANSITION_SPHERICAL } |
Public Member Functions | |
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. | |
TabletViewController () | |
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 | ~TabletViewController () |
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 | updateMousePointPublishTopics () |
void | updatePublishTopics () |
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 | publishCurrentPlacement () |
void | publishMouseEvent (rviz::ViewportMouseEvent &event) |
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_publish_topic_property_ |
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. | |
rviz::RosTopicProperty * | mouse_point_publish_topic_property_ |
ros::Publisher | mouse_point_publisher_ |
ros::NodeHandle | nh_ |
ros::Publisher | placement_publisher_ |
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 62 of file tablet_view_controller.h.
anonymous enum |
Definition at line 67 of file tablet_view_controller.h.
Definition at line 102 of file tablet_view_controller.cpp.
Definition at line 154 of file tablet_view_controller.cpp.
Ogre::Vector3 jsk_rviz_plugins::TabletViewController::attachedLocalToFixedFrame | ( | const Ogre::Vector3 & | v | ) | [inline, protected] |
Definition at line 191 of file tablet_view_controller.h.
void jsk_rviz_plugins::TabletViewController::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 585 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::cameraPlacementCallback | ( | const view_controller_msgs::CameraPlacementConstPtr & | cp_ptr | ) | [protected] |
Definition at line 619 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::cancelTransition | ( | ) | [protected] |
Cancels any currently active camera movement.
Definition at line 614 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::connectPositionProperties | ( | ) | [protected] |
Convenience function; connects the signals/slots for position properties.
Definition at line 263 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::disconnectPositionProperties | ( | ) | [protected] |
Convenience function; disconnects the signals/slots for position properties.
Definition at line 271 of file tablet_view_controller.cpp.
Ogre::Vector3 jsk_rviz_plugins::TabletViewController::fixedFrameToAttachedLocal | ( | const Ogre::Vector3 & | v | ) | [inline, protected] |
Definition at line 190 of file tablet_view_controller.h.
float jsk_rviz_plugins::TabletViewController::getDistanceFromCameraToFocalPoint | ( | ) | [protected] |
Return the distance between camera and focal point.
Definition at line 362 of file tablet_view_controller.cpp.
Ogre::Quaternion jsk_rviz_plugins::TabletViewController::getOrientation | ( | ) | [protected] |
Return a Quaternion.
Definition at line 836 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::handleMouseEvent | ( | rviz::ViewportMouseEvent & | evt | ) | [virtual] |
Reimplemented from rviz::ViewController.
Definition at line 386 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::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 719 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::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 540 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::move_eye | ( | float | x, |
float | y, | ||
float | z | ||
) |
Applies a translation to only the eye point.
Definition at line 848 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::move_focus_and_eye | ( | float | x, |
float | y, | ||
float | z | ||
) |
Applies a translation to the focus and eye points.
Definition at line 841 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::moveEyeWithFocusTo | ( | const Ogre::Vector3 & | point | ) |
Calls beginNewTransition() to move the eye to the point given, keeping the direction fixed.
Definition at line 741 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::onActivate | ( | ) | [virtual] |
called by activate().
This version calls updateAttachedSceneNode().
Reimplemented from rviz::ViewController.
Definition at line 243 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::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 342 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::onDistancePropertyChanged | ( | ) | [protected, virtual, slot] |
Called when distance property is changed; computes new eye position.
Definition at line 289 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::onEyePropertyChanged | ( | ) | [protected, virtual, slot] |
Called when eye property is changed; computes new distance.
Definition at line 279 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::onFocusPropertyChanged | ( | ) | [protected, virtual, slot] |
Called focus property is changed; computes new distance.
Definition at line 284 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::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 227 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::onUpPropertyChanged | ( | ) | [protected, virtual, slot] |
Called when up vector property is changed (does nothing for now...).
Definition at line 297 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::orbitCameraTo | ( | const Ogre::Vector3 & | point | ) |
Calls beginNewTransition() with the focus point fixed, moving the eye to the point given.
Definition at line 734 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::publishCurrentPlacement | ( | ) | [protected] |
Definition at line 186 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::publishMouseEvent | ( | rviz::ViewportMouseEvent & | event | ) | [protected] |
Definition at line 172 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::reset | ( | ) | [virtual] |
Resets the camera parameters to a sane value.
Implements rviz::ViewController.
Definition at line 367 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::setPropertiesFromCamera | ( | Ogre::Camera * | source_camera | ) | [protected] |
Definition at line 525 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::transformCameraPlacementToAttachedFrame | ( | view_controller_msgs::CameraPlacement & | cp | ) | [protected] |
Definition at line 690 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::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 568 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::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 749 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::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 314 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::updateAttachedSceneNode | ( | ) | [protected] |
Update the position of the attached_scene_node_ from the TF frame specified in the Attached Frame property.
Definition at line 324 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::updateCamera | ( | ) | [protected] |
Updates the Ogre camera properties from the view controller properties.
Definition at line 785 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::updateMousePointPublishTopics | ( | ) | [protected, slot] |
Definition at line 166 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::updatePublishTopics | ( | ) | [protected, slot] |
Definition at line 160 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::updateTopics | ( | ) | [protected, slot] |
Definition at line 217 of file tablet_view_controller.cpp.
void jsk_rviz_plugins::TabletViewController::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 794 of file tablet_view_controller.cpp.
bool jsk_rviz_plugins::TabletViewController::animate_ [protected] |
Definition at line 229 of file tablet_view_controller.h.
Definition at line 222 of file tablet_view_controller.h.
Ogre::SceneNode* jsk_rviz_plugins::TabletViewController::attached_scene_node_ [protected] |
Definition at line 223 of file tablet_view_controller.h.
rviz::RosTopicProperty* jsk_rviz_plugins::TabletViewController::camera_placement_publish_topic_property_ [protected] |
Definition at line 218 of file tablet_view_controller.h.
rviz::RosTopicProperty* jsk_rviz_plugins::TabletViewController::camera_placement_topic_property_ [protected] |
Definition at line 217 of file tablet_view_controller.h.
Definition at line 235 of file tablet_view_controller.h.
rviz::FloatProperty* jsk_rviz_plugins::TabletViewController::default_transition_time_property_ [protected] |
A default time for any animation requests.
Definition at line 215 of file tablet_view_controller.h.
The camera's distance from the focal point.
Definition at line 211 of file tablet_view_controller.h.
bool jsk_rviz_plugins::TabletViewController::dragging_ [protected] |
A flag indicating the dragging state of the mouse.
Definition at line 238 of file tablet_view_controller.h.
The position of the camera.
Definition at line 212 of file tablet_view_controller.h.
If True, "up" is fixed to ... up.
Definition at line 209 of file tablet_view_controller.h.
A small ellipsoid to show the focus point.
Definition at line 237 of file tablet_view_controller.h.
The point around which the camera "orbits".
Definition at line 213 of file tablet_view_controller.h.
Ogre::Vector3 jsk_rviz_plugins::TabletViewController::goal_focus_ [protected] |
Definition at line 231 of file tablet_view_controller.h.
Ogre::Vector3 jsk_rviz_plugins::TabletViewController::goal_position_ [protected] |
Definition at line 230 of file tablet_view_controller.h.
Ogre::Vector3 jsk_rviz_plugins::TabletViewController::goal_up_ [protected] |
Definition at line 232 of file tablet_view_controller.h.
QCursor jsk_rviz_plugins::TabletViewController::interaction_disabled_cursor_ [protected] |
A cursor for indicating mouse interaction is disabled.
Definition at line 240 of file tablet_view_controller.h.
rviz::EditableEnumProperty* jsk_rviz_plugins::TabletViewController::interaction_mode_property_ [protected] |
Select between Orbit or FPS control style.
Definition at line 208 of file tablet_view_controller.h.
If True, most user changes to camera state are disabled.
Definition at line 207 of file tablet_view_controller.h.
rviz::RosTopicProperty* jsk_rviz_plugins::TabletViewController::mouse_point_publish_topic_property_ [protected] |
Definition at line 219 of file tablet_view_controller.h.
Definition at line 247 of file tablet_view_controller.h.
Definition at line 205 of file tablet_view_controller.h.
Definition at line 245 of file tablet_view_controller.h.
Definition at line 243 of file tablet_view_controller.h.
Ogre::Quaternion jsk_rviz_plugins::TabletViewController::reference_orientation_ [protected] |
Used to store the orientation of the attached frame relative to <Fixed frame>="">
Definition at line 225 of file tablet_view_controller.h.
Ogre::Vector3 jsk_rviz_plugins::TabletViewController::reference_position_ [protected] |
Used to store the position of the attached frame relative to <Fixed frame>="">
Definition at line 226 of file tablet_view_controller.h.
Ogre::Vector3 jsk_rviz_plugins::TabletViewController::start_focus_ [protected] |
Definition at line 231 of file tablet_view_controller.h.
Ogre::Vector3 jsk_rviz_plugins::TabletViewController::start_position_ [protected] |
Definition at line 230 of file tablet_view_controller.h.
Ogre::Vector3 jsk_rviz_plugins::TabletViewController::start_up_ [protected] |
Definition at line 232 of file tablet_view_controller.h.
Definition at line 233 of file tablet_view_controller.h.
Definition at line 234 of file tablet_view_controller.h.
The up vector for the camera.
Definition at line 214 of file tablet_view_controller.h.