Public Types | Public Member Functions | Protected Slots | Protected Member Functions | Protected Attributes
jsk_rviz_plugins::TabletViewController Class Reference

An un-constrained "flying" camera, specified by an eye point, focus point, and up vector. More...

#include <tablet_view_controller.h>

Inheritance diagram for jsk_rviz_plugins::TabletViewController:
Inheritance graph
[legend]

List of all members.

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::TfFramePropertyattached_frame_property_
Ogre::SceneNode * attached_scene_node_
rviz::RosTopicPropertycamera_placement_publish_topic_property_
rviz::RosTopicPropertycamera_placement_topic_property_
ros::Duration current_transition_duration_
rviz::FloatPropertydefault_transition_time_property_
 A default time for any animation requests.
rviz::FloatPropertydistance_property_
 The camera's distance from the focal point.
bool dragging_
 A flag indicating the dragging state of the mouse.
rviz::VectorPropertyeye_point_property_
 The position of the camera.
rviz::BoolPropertyfixed_up_property_
 If True, "up" is fixed to ... up.
rviz::Shapefocal_shape_
 A small ellipsoid to show the focus point.
rviz::VectorPropertyfocus_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::EditableEnumPropertyinteraction_mode_property_
 Select between Orbit or FPS control style.
rviz::BoolPropertymouse_enabled_property_
 If True, most user changes to camera state are disabled.
rviz::RosTopicPropertymouse_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::VectorPropertyup_vector_property_
 The up vector for the camera.

Detailed Description

An un-constrained "flying" camera, specified by an eye point, focus point, and up vector.

Definition at line 64 of file tablet_view_controller.h.


Member Enumeration Documentation

anonymous enum
Enumerator:
TRANSITION_LINEAR 
TRANSITION_SPHERICAL 

Definition at line 69 of file tablet_view_controller.h.


Constructor & Destructor Documentation

Definition at line 102 of file tablet_view_controller.cpp.

Definition at line 154 of file tablet_view_controller.cpp.


Member Function Documentation

Definition at line 193 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.

Cancels any currently active camera movement.

Definition at line 614 of file tablet_view_controller.cpp.

Convenience function; connects the signals/slots for position properties.

Definition at line 263 of file tablet_view_controller.cpp.

Convenience function; disconnects the signals/slots for position properties.

Definition at line 271 of file tablet_view_controller.cpp.

Definition at line 192 of file tablet_view_controller.h.

Return the distance between camera and focal point.

Definition at line 362 of file tablet_view_controller.cpp.

Return a Quaternion.

Definition at line 836 of file tablet_view_controller.cpp.

Reimplemented from rviz::ViewController.

Definition at line 386 of file tablet_view_controller.cpp.

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.

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.

Calls beginNewTransition() to move the eye to the point given, keeping the direction fixed.

Definition at line 741 of file tablet_view_controller.cpp.

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.

See also:
updateAttachedFrame()

Definition at line 342 of file tablet_view_controller.cpp.

Called when distance property is changed; computes new eye position.

Definition at line 289 of file tablet_view_controller.cpp.

Called when eye property is changed; computes new distance.

Definition at line 279 of file tablet_view_controller.cpp.

Called focus property is changed; computes new distance.

Definition at line 284 of file tablet_view_controller.cpp.

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.

Called when up vector property is changed (does nothing for now...).

Definition at line 297 of file tablet_view_controller.cpp.

Calls beginNewTransition() with the focus point fixed, moving the eye to the point given.

Definition at line 734 of file tablet_view_controller.cpp.

Definition at line 186 of file tablet_view_controller.cpp.

Definition at line 172 of file tablet_view_controller.cpp.

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.

Called by ViewManager when this ViewController is being made current.

Parameters:
previous_viewis 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.

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.

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.

Updates the Ogre camera properties from the view controller properties.

Definition at line 785 of file tablet_view_controller.cpp.

Definition at line 166 of file tablet_view_controller.cpp.

Definition at line 160 of file tablet_view_controller.cpp.

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.


Member Data Documentation

Definition at line 231 of file tablet_view_controller.h.

Definition at line 224 of file tablet_view_controller.h.

Definition at line 225 of file tablet_view_controller.h.

Definition at line 220 of file tablet_view_controller.h.

Definition at line 219 of file tablet_view_controller.h.

Definition at line 237 of file tablet_view_controller.h.

A default time for any animation requests.

Definition at line 217 of file tablet_view_controller.h.

The camera's distance from the focal point.

Definition at line 213 of file tablet_view_controller.h.

A flag indicating the dragging state of the mouse.

Definition at line 240 of file tablet_view_controller.h.

The position of the camera.

Definition at line 214 of file tablet_view_controller.h.

If True, "up" is fixed to ... up.

Definition at line 211 of file tablet_view_controller.h.

A small ellipsoid to show the focus point.

Definition at line 239 of file tablet_view_controller.h.

The point around which the camera "orbits".

Definition at line 215 of file tablet_view_controller.h.

Definition at line 233 of file tablet_view_controller.h.

Definition at line 232 of file tablet_view_controller.h.

Definition at line 234 of file tablet_view_controller.h.

A cursor for indicating mouse interaction is disabled.

Definition at line 242 of file tablet_view_controller.h.

Select between Orbit or FPS control style.

Definition at line 210 of file tablet_view_controller.h.

If True, most user changes to camera state are disabled.

Definition at line 209 of file tablet_view_controller.h.

Definition at line 221 of file tablet_view_controller.h.

Definition at line 249 of file tablet_view_controller.h.

Definition at line 207 of file tablet_view_controller.h.

Definition at line 247 of file tablet_view_controller.h.

Definition at line 245 of file tablet_view_controller.h.

Used to store the orientation of the attached frame relative to <Fixed frame>="">

Definition at line 227 of file tablet_view_controller.h.

Used to store the position of the attached frame relative to <Fixed frame>="">

Definition at line 228 of file tablet_view_controller.h.

Definition at line 233 of file tablet_view_controller.h.

Definition at line 232 of file tablet_view_controller.h.

Definition at line 234 of file tablet_view_controller.h.

Definition at line 235 of file tablet_view_controller.h.

Definition at line 236 of file tablet_view_controller.h.

The up vector for the camera.

Definition at line 216 of file tablet_view_controller.h.


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


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Wed May 1 2019 02:40:22