Go to the documentation of this file.
33 #ifndef JSK_RVIZ_PLUGINS_TABLET_VIEW_CONTROLLER_H_
34 #define JSK_RVIZ_PLUGINS_TABLET_VIEW_CONTROLLER_H_
42 #include "view_controller_msgs/CameraPlacement.h"
44 #include <OGRE/OgreVector3.h>
45 #include <OGRE/OgreQuaternion.h>
54 class QuaternionProperty;
55 class TfFrameProperty;
56 class EditableEnumProperty;
57 class RosTopicProperty;
104 virtual void lookAt(
const Ogre::Vector3& point );
114 virtual void reset();
157 virtual void update(
float dt,
float ros_dt);
168 virtual void onAttachedFrameChanged(
const Ogre::Vector3& old_reference_position,
const Ogre::Quaternion& old_reference_orientation );
183 void beginNewTransition(
const Ogre::Vector3 &eye,
const Ogre::Vector3 &focus,
const Ogre::Vector3 &up,
254 #endif // RVIZ_ANIMATED_VIEW_CONTROLLER_H
Ogre::SceneNode * attached_scene_node_
rviz::RosTopicProperty * camera_placement_publish_topic_property_
virtual void mimic(ViewController *source_view)
Configure the settings of this view controller to give, as much as possible, a similar view as that g...
virtual void transitionFrom(ViewController *previous_view)
Called by ViewManager when this ViewController is being made current.
virtual void onFocusPropertyChanged()
Called focus property is changed; computes new distance.
rviz::VectorProperty * up_vector_property_
The up vector for the camera.
rviz::VectorProperty * eye_point_property_
The position of the camera.
virtual void onActivate()
called by activate().
rviz::Shape * focal_shape_
A small ellipsoid to show the focus point.
void move_focus_and_eye(float x, float y, float z)
Applies a translation to the focus and eye points.
Ogre::Vector3 goal_position_
void yaw_pitch_roll(float yaw, float pitch, float roll)
Applies a body-fixed-axes sequence of rotations; only accurate for small angles.
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 r...
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.
Ogre::Vector3 start_position_
rviz::BoolProperty * fixed_up_property_
If True, "up" is fixed to ... up.
rviz::VectorProperty * focus_point_property_
The point around which the camera "orbits".
void connectPositionProperties()
Convenience function; connects the signals/slots for position properties.
Ogre::Vector3 attachedLocalToFixedFrame(const Ogre::Vector3 &v)
virtual void onEyePropertyChanged()
Called when eye property is changed; computes new distance.
ros::Time transition_start_time_
ros::Publisher mouse_point_publisher_
void orbitCameraTo(const Ogre::Vector3 &point)
Calls beginNewTransition() with the focus point fixed, moving the eye to the point given.
virtual void onInitialize()
Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ ...
rviz::BoolProperty * mouse_enabled_property_
If True, most user changes to camera state are disabled.
rviz::TfFrameProperty * attached_frame_property_
bool dragging_
A flag indicating the dragging state of the mouse.
virtual void reset()
Resets the camera parameters to a sane value.
void updateCamera()
Updates the Ogre camera properties from the view controller properties.
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.
rviz::FloatProperty * default_transition_time_property_
A default time for any animation requests.
void move_eye(float x, float y, float z)
Applies a translation to only the eye point.
void updateAttachedSceneNode()
Update the position of the attached_scene_node_ from the TF frame specified in the Attached Frame pro...
void cancelTransition()
Cancels any currently active camera movement.
float getDistanceFromCameraToFocalPoint()
Return the distance between camera and focal point.
void setPropertiesFromCamera(Ogre::Camera *source_camera)
ros::Duration current_transition_duration_
ros::Time trajectory_start_time_
void moveEyeWithFocusTo(const Ogre::Vector3 &point)
Calls beginNewTransition() to move the eye to the point given, keeping the direction fixed.
void publishCurrentPlacement()
rviz::RosTopicProperty * mouse_point_publish_topic_property_
virtual void onDistancePropertyChanged()
Called when distance property is changed; computes new eye position.
Ogre::Vector3 goal_focus_
ros::Publisher placement_publisher_
Ogre::Quaternion getOrientation()
Return a Quaternion.
Ogre::Vector3 reference_position_
Used to store the position of the attached frame relative to <Fixed Frame>
void disconnectPositionProperties()
Convenience function; disconnects the signals/slots for position properties.
An un-constrained "flying" camera, specified by an eye point, focus point, and up vector.
QCursor interaction_disabled_cursor_
A cursor for indicating mouse interaction is disabled.
rviz::EditableEnumProperty * interaction_mode_property_
Select between Orbit or FPS control style.
Ogre::Vector3 fixedFrameToAttachedLocal(const Ogre::Vector3 &v)
virtual ~TabletViewController()
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 vi...
void updateMousePointPublishTopics()
virtual void lookAt(const Ogre::Vector3 &point)
Calls beginNewTransition() to move the focus point to the point provided, assumed to be in the Rviz F...
rviz::RosTopicProperty * camera_placement_topic_property_
rviz::FloatProperty * distance_property_
The camera's distance from the focal point.
Ogre::Quaternion reference_orientation_
Used to store the orientation of the attached frame relative to <Fixed Frame>
Ogre::Vector3 start_focus_
void cameraPlacementCallback(const view_controller_msgs::CameraPlacementConstPtr &cp_ptr)
void updatePublishTopics()
virtual void handleMouseEvent(rviz::ViewportMouseEvent &evt)
void transformCameraPlacementToAttachedFrame(view_controller_msgs::CameraPlacement &cp)
ros::Subscriber placement_subscriber_
void publishMouseEvent(rviz::ViewportMouseEvent &event)
jsk_rviz_plugins
Author(s): Kei Okada
, Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Fri Aug 2 2024 08:50:15