tablet_view_controller.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, JSK Lab, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the JSK Lab, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Author: Adam Leeper
30  * Author: Ryohei Ueda
31  */
32 
33 #ifndef JSK_RVIZ_PLUGINS_TABLET_VIEW_CONTROLLER_H_
34 #define JSK_RVIZ_PLUGINS_TABLET_VIEW_CONTROLLER_H_
35 
36 #ifndef Q_MOC_RUN
37 #include "rviz/view_controller.h"
38 
39 #include <ros/subscriber.h>
40 #include <ros/ros.h>
41 
42 #include "view_controller_msgs/CameraPlacement.h"
43 
44 #include <OGRE/OgreVector3.h>
45 #include <OGRE/OgreQuaternion.h>
46 #endif
47 
48 namespace rviz {
49  class SceneNode;
50  class Shape;
51  class BoolProperty;
52  class FloatProperty;
53  class VectorProperty;
54  class QuaternionProperty;
55  class TfFrameProperty;
56  class EditableEnumProperty;
57  class RosTopicProperty;
58 }
59 
60 namespace jsk_rviz_plugins
61 {
62 
65 {
66 Q_OBJECT
67 public:
68 
69  enum { TRANSITION_LINEAR = 0,
71 
73  virtual ~TabletViewController();
74 
79  virtual void onInitialize();
80 
84  virtual void onActivate();
85 
86 
88  void move_focus_and_eye( float x, float y, float z );
89 
91  void move_eye( float x, float y, float z );
92 
93 
96  void yaw_pitch_roll( float yaw, float pitch, float roll );
97 
98 
99  virtual void handleMouseEvent(rviz::ViewportMouseEvent& evt);
100 
101 
104  virtual void lookAt( const Ogre::Vector3& point );
105 
106 
108  void orbitCameraTo( const Ogre::Vector3& point);
109 
111  void moveEyeWithFocusTo( const Ogre::Vector3& point);
112 
114  virtual void reset();
115 
121  virtual void mimic( ViewController* source_view );
122 
130  virtual void transitionFrom( ViewController* previous_view );
131 
132 
133 protected Q_SLOTS:
139  virtual void updateAttachedFrame();
140 
142  virtual void onDistancePropertyChanged();
143 
145  virtual void onFocusPropertyChanged();
146 
148  virtual void onEyePropertyChanged();
149 
151  virtual void onUpPropertyChanged();
152 
153 protected: //methods
154 
157  virtual void update(float dt, float ros_dt);
158 
161 
164 
168  virtual void onAttachedFrameChanged( const Ogre::Vector3& old_reference_position, const Ogre::Quaternion& old_reference_orientation );
169 
173 
174  void cameraPlacementCallback(const view_controller_msgs::CameraPlacementConstPtr &cp_ptr);
175  //void cameraPlacementTrajectoryCallback(const view_controller_msgs::CameraPlacementTrajectoryConstPtr &cptptr);
176  void transformCameraPlacementToAttachedFrame(view_controller_msgs::CameraPlacement &cp);
177 
178  //void setUpVectorPropertyModeDependent( const Ogre::Vector3 &vector );
179 
180  void setPropertiesFromCamera( Ogre::Camera* source_camera );
181 
183  void beginNewTransition(const Ogre::Vector3 &eye, const Ogre::Vector3 &focus, const Ogre::Vector3 &up,
184  const ros::Duration &transition_time);
185 
187  void cancelTransition();
188 
190  void updateCamera();
191 
192  Ogre::Vector3 fixedFrameToAttachedLocal(const Ogre::Vector3 &v) { return reference_orientation_.Inverse()*(v - reference_position_); }
193  Ogre::Vector3 attachedLocalToFixedFrame(const Ogre::Vector3 &v) { return reference_position_ + (reference_orientation_*v); }
194 
196 
199  Ogre::Quaternion getOrientation();
200 
201 protected Q_SLOTS:
202  void updateTopics();
203  void updatePublishTopics();
205 protected: //members
206 
208 
212 
218 
222 // rviz::RosTopicProperty* camera_placement_trajectory_topic_property_;
223 
225  Ogre::SceneNode* attached_scene_node_;
226 
227  Ogre::Quaternion reference_orientation_;
228  Ogre::Vector3 reference_position_;
229 
230  // Variables used during animation
231  bool animate_;
233  Ogre::Vector3 start_focus_, goal_focus_;
234  Ogre::Vector3 start_up_, goal_up_;
238 
240  bool dragging_;
241 
243 
244 // ros::Subscriber trajectory_subscriber_;
246 
248 
250 };
251 
252 } // namespace rviz_animated_view_controller
253 
254 #endif // RVIZ_ANIMATED_VIEW_CONTROLLER_H
jsk_rviz_plugins::TabletViewController::attached_scene_node_
Ogre::SceneNode * attached_scene_node_
Definition: tablet_view_controller.h:225
jsk_rviz_plugins::TabletViewController::camera_placement_publish_topic_property_
rviz::RosTopicProperty * camera_placement_publish_topic_property_
Definition: tablet_view_controller.h:220
jsk_rviz_plugins::TabletViewController::mimic
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...
Definition: tablet_view_controller.cpp:540
rviz::RosTopicProperty
ros::Publisher
jsk_rviz_plugins::TabletViewController::transitionFrom
virtual void transitionFrom(ViewController *previous_view)
Called by ViewManager when this ViewController is being made current.
Definition: tablet_view_controller.cpp:568
jsk_rviz_plugins::TabletViewController::onFocusPropertyChanged
virtual void onFocusPropertyChanged()
Called focus property is changed; computes new distance.
Definition: tablet_view_controller.cpp:284
jsk_rviz_plugins::TabletViewController::up_vector_property_
rviz::VectorProperty * up_vector_property_
The up vector for the camera.
Definition: tablet_view_controller.h:216
view_controller.h
ros.h
bounding_box_sample.z
z
Definition: bounding_box_sample.py:28
rviz::EditableEnumProperty
rviz::BoolProperty
rviz::ViewportMouseEvent
jsk_rviz_plugins::TabletViewController::eye_point_property_
rviz::VectorProperty * eye_point_property_
The position of the camera.
Definition: tablet_view_controller.h:214
jsk_rviz_plugins::TabletViewController::onActivate
virtual void onActivate()
called by activate().
Definition: tablet_view_controller.cpp:243
jsk_rviz_plugins::TabletViewController::focal_shape_
rviz::Shape * focal_shape_
A small ellipsoid to show the focus point.
Definition: tablet_view_controller.h:239
jsk_rviz_plugins::TabletViewController::move_focus_and_eye
void move_focus_and_eye(float x, float y, float z)
Applies a translation to the focus and eye points.
Definition: tablet_view_controller.cpp:841
jsk_rviz_plugins::TabletViewController::start_up_
Ogre::Vector3 start_up_
Definition: tablet_view_controller.h:234
jsk_rviz_plugins::TabletViewController::goal_position_
Ogre::Vector3 goal_position_
Definition: tablet_view_controller.h:232
jsk_rviz_plugins::TabletViewController::yaw_pitch_roll
void yaw_pitch_roll(float yaw, float pitch, float roll)
Applies a body-fixed-axes sequence of rotations; only accurate for small angles.
Definition: tablet_view_controller.cpp:794
jsk_rviz_plugins::TabletViewController::update
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...
Definition: tablet_view_controller.cpp:749
jsk_rviz_plugins::TabletViewController::beginNewTransition
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.
Definition: tablet_view_controller.cpp:585
jsk_rviz_plugins::TabletViewController::start_position_
Ogre::Vector3 start_position_
Definition: tablet_view_controller.h:232
jsk_rviz_plugins::TabletViewController::fixed_up_property_
rviz::BoolProperty * fixed_up_property_
If True, "up" is fixed to ... up.
Definition: tablet_view_controller.h:211
rviz::FloatProperty
jsk_rviz_plugins::TabletViewController::focus_point_property_
rviz::VectorProperty * focus_point_property_
The point around which the camera "orbits".
Definition: tablet_view_controller.h:215
jsk_rviz_plugins::TabletViewController::connectPositionProperties
void connectPositionProperties()
Convenience function; connects the signals/slots for position properties.
Definition: tablet_view_controller.cpp:263
jsk_rviz_plugins::TabletViewController::attachedLocalToFixedFrame
Ogre::Vector3 attachedLocalToFixedFrame(const Ogre::Vector3 &v)
Definition: tablet_view_controller.h:193
jsk_rviz_plugins::TabletViewController::onEyePropertyChanged
virtual void onEyePropertyChanged()
Called when eye property is changed; computes new distance.
Definition: tablet_view_controller.cpp:279
jsk_rviz_plugins::TabletViewController::transition_start_time_
ros::Time transition_start_time_
Definition: tablet_view_controller.h:236
jsk_rviz_plugins::TabletViewController::mouse_point_publisher_
ros::Publisher mouse_point_publisher_
Definition: tablet_view_controller.h:249
jsk_rviz_plugins::TabletViewController::orbitCameraTo
void orbitCameraTo(const Ogre::Vector3 &point)
Calls beginNewTransition() with the focus point fixed, moving the eye to the point given.
Definition: tablet_view_controller.cpp:734
jsk_rviz_plugins::TabletViewController::onInitialize
virtual void onInitialize()
Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ ...
Definition: tablet_view_controller.cpp:227
rviz
jsk_rviz_plugins::TabletViewController::mouse_enabled_property_
rviz::BoolProperty * mouse_enabled_property_
If True, most user changes to camera state are disabled.
Definition: tablet_view_controller.h:209
subscriber.h
jsk_rviz_plugins::TabletViewController::TabletViewController
TabletViewController()
Definition: tablet_view_controller.cpp:102
jsk_rviz_plugins::TabletViewController::attached_frame_property_
rviz::TfFrameProperty * attached_frame_property_
Definition: tablet_view_controller.h:224
jsk_rviz_plugins::TabletViewController::dragging_
bool dragging_
A flag indicating the dragging state of the mouse.
Definition: tablet_view_controller.h:240
bounding_box_sample.x
x
Definition: bounding_box_sample.py:26
jsk_rviz_plugins::TabletViewController::updateTopics
void updateTopics()
Definition: tablet_view_controller.cpp:217
jsk_rviz_plugins::TabletViewController::reset
virtual void reset()
Resets the camera parameters to a sane value.
Definition: tablet_view_controller.cpp:367
jsk_rviz_plugins::TabletViewController::TRANSITION_LINEAR
@ TRANSITION_LINEAR
Definition: tablet_view_controller.h:69
jsk_rviz_plugins::TabletViewController::updateCamera
void updateCamera()
Updates the Ogre camera properties from the view controller properties.
Definition: tablet_view_controller.cpp:785
jsk_rviz_plugins::TabletViewController::onAttachedFrameChanged
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.
Definition: tablet_view_controller.cpp:342
jsk_rviz_plugins::TabletViewController::default_transition_time_property_
rviz::FloatProperty * default_transition_time_property_
A default time for any animation requests.
Definition: tablet_view_controller.h:217
jsk_rviz_plugins::TabletViewController::move_eye
void move_eye(float x, float y, float z)
Applies a translation to only the eye point.
Definition: tablet_view_controller.cpp:848
jsk_rviz_plugins::TabletViewController::updateAttachedSceneNode
void updateAttachedSceneNode()
Update the position of the attached_scene_node_ from the TF frame specified in the Attached Frame pro...
Definition: tablet_view_controller.cpp:324
jsk_rviz_plugins::TabletViewController::cancelTransition
void cancelTransition()
Cancels any currently active camera movement.
Definition: tablet_view_controller.cpp:614
jsk_rviz_plugins::TabletViewController::getDistanceFromCameraToFocalPoint
float getDistanceFromCameraToFocalPoint()
Return the distance between camera and focal point.
Definition: tablet_view_controller.cpp:362
jsk_rviz_plugins::TabletViewController::setPropertiesFromCamera
void setPropertiesFromCamera(Ogre::Camera *source_camera)
Definition: tablet_view_controller.cpp:525
jsk_rviz_plugins::TabletViewController::current_transition_duration_
ros::Duration current_transition_duration_
Definition: tablet_view_controller.h:237
jsk_rviz_plugins::TabletViewController::trajectory_start_time_
ros::Time trajectory_start_time_
Definition: tablet_view_controller.h:235
jsk_rviz_plugins::TabletViewController::moveEyeWithFocusTo
void moveEyeWithFocusTo(const Ogre::Vector3 &point)
Calls beginNewTransition() to move the eye to the point given, keeping the direction fixed.
Definition: tablet_view_controller.cpp:741
jsk_rviz_plugins::TabletViewController::publishCurrentPlacement
void publishCurrentPlacement()
Definition: tablet_view_controller.cpp:186
bounding_box_sample.y
y
Definition: bounding_box_sample.py:27
jsk_rviz_plugins::TabletViewController::mouse_point_publish_topic_property_
rviz::RosTopicProperty * mouse_point_publish_topic_property_
Definition: tablet_view_controller.h:221
jsk_rviz_plugins::TabletViewController::onDistancePropertyChanged
virtual void onDistancePropertyChanged()
Called when distance property is changed; computes new eye position.
Definition: tablet_view_controller.cpp:289
rviz::TfFrameProperty
jsk_rviz_plugins::TabletViewController::goal_focus_
Ogre::Vector3 goal_focus_
Definition: tablet_view_controller.h:233
jsk_rviz_plugins::TabletViewController::animate_
bool animate_
Definition: tablet_view_controller.h:231
jsk_rviz_plugins::TabletViewController::placement_publisher_
ros::Publisher placement_publisher_
Definition: tablet_view_controller.h:247
jsk_rviz_plugins::TabletViewController::getOrientation
Ogre::Quaternion getOrientation()
Return a Quaternion.
Definition: tablet_view_controller.cpp:836
ros::Time
jsk_rviz_plugins::TabletViewController::reference_position_
Ogre::Vector3 reference_position_
Used to store the position of the attached frame relative to <Fixed Frame>
Definition: tablet_view_controller.h:228
rviz::ViewController
jsk_rviz_plugins::TabletViewController::disconnectPositionProperties
void disconnectPositionProperties()
Convenience function; disconnects the signals/slots for position properties.
Definition: tablet_view_controller.cpp:271
jsk_rviz_plugins::TabletViewController
An un-constrained "flying" camera, specified by an eye point, focus point, and up vector.
Definition: tablet_view_controller.h:64
jsk_rviz_plugins::TabletViewController::interaction_disabled_cursor_
QCursor interaction_disabled_cursor_
A cursor for indicating mouse interaction is disabled.
Definition: tablet_view_controller.h:242
jsk_rviz_plugins::TabletViewController::interaction_mode_property_
rviz::EditableEnumProperty * interaction_mode_property_
Select between Orbit or FPS control style.
Definition: tablet_view_controller.h:210
jsk_rviz_plugins::TabletViewController::TRANSITION_SPHERICAL
@ TRANSITION_SPHERICAL
Definition: tablet_view_controller.h:70
jsk_rviz_plugins::TabletViewController::fixedFrameToAttachedLocal
Ogre::Vector3 fixedFrameToAttachedLocal(const Ogre::Vector3 &v)
Definition: tablet_view_controller.h:192
rviz::Shape
jsk_rviz_plugins::TabletViewController::~TabletViewController
virtual ~TabletViewController()
Definition: tablet_view_controller.cpp:154
jsk_rviz_plugins::TabletViewController::onUpPropertyChanged
virtual void onUpPropertyChanged()
Called when up vector property is changed (does nothing for now...).
Definition: tablet_view_controller.cpp:297
jsk_rviz_plugins::TabletViewController::updateAttachedFrame
virtual void updateAttachedFrame()
Called when Target Frame property changes while view is active. Purpose is to change values in the vi...
Definition: tablet_view_controller.cpp:314
jsk_rviz_plugins::TabletViewController::updateMousePointPublishTopics
void updateMousePointPublishTopics()
Definition: tablet_view_controller.cpp:166
jsk_rviz_plugins::TabletViewController::lookAt
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...
Definition: tablet_view_controller.cpp:719
jsk_rviz_plugins::TabletViewController::goal_up_
Ogre::Vector3 goal_up_
Definition: tablet_view_controller.h:234
jsk_rviz_plugins::TabletViewController::camera_placement_topic_property_
rviz::RosTopicProperty * camera_placement_topic_property_
Definition: tablet_view_controller.h:219
rviz::VectorProperty
jsk_rviz_plugins::TabletViewController::distance_property_
rviz::FloatProperty * distance_property_
The camera's distance from the focal point.
Definition: tablet_view_controller.h:213
jsk_rviz_plugins::TabletViewController::reference_orientation_
Ogre::Quaternion reference_orientation_
Used to store the orientation of the attached frame relative to <Fixed Frame>
Definition: tablet_view_controller.h:227
jsk_rviz_plugins::TabletViewController::start_focus_
Ogre::Vector3 start_focus_
Definition: tablet_view_controller.h:233
jsk_rviz_plugins::TabletViewController::nh_
ros::NodeHandle nh_
Definition: tablet_view_controller.h:207
jsk_rviz_plugins::TabletViewController::cameraPlacementCallback
void cameraPlacementCallback(const view_controller_msgs::CameraPlacementConstPtr &cp_ptr)
Definition: tablet_view_controller.cpp:619
ros::Duration
jsk_rviz_plugins
Definition: __init__.py:1
jsk_rviz_plugins::TabletViewController::updatePublishTopics
void updatePublishTopics()
Definition: tablet_view_controller.cpp:160
jsk_rviz_plugins::TabletViewController::handleMouseEvent
virtual void handleMouseEvent(rviz::ViewportMouseEvent &evt)
Definition: tablet_view_controller.cpp:386
jsk_rviz_plugins::TabletViewController::transformCameraPlacementToAttachedFrame
void transformCameraPlacementToAttachedFrame(view_controller_msgs::CameraPlacement &cp)
Definition: tablet_view_controller.cpp:690
ros::NodeHandle
ros::Subscriber
jsk_rviz_plugins::TabletViewController::placement_subscriber_
ros::Subscriber placement_subscriber_
Definition: tablet_view_controller.h:245
jsk_rviz_plugins::TabletViewController::publishMouseEvent
void publishMouseEvent(rviz::ViewportMouseEvent &event)
Definition: tablet_view_controller.cpp:172


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Mon Jan 22 2024 03:47:13