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,
70  TRANSITION_SPHERICAL};
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 
160  void connectPositionProperties();
161 
163  void disconnectPositionProperties();
164 
168  virtual void onAttachedFrameChanged( const Ogre::Vector3& old_reference_position, const Ogre::Quaternion& old_reference_orientation );
169 
172  void updateAttachedSceneNode();
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 
195  float getDistanceFromCameraToFocalPoint();
196 
197  void publishCurrentPlacement();
198  void publishMouseEvent(rviz::ViewportMouseEvent& event);
199  Ogre::Quaternion getOrientation();
200 
201 protected Q_SLOTS:
202  void updateTopics();
203  void updatePublishTopics();
204  void updateMousePointPublishTopics();
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_;
232  Ogre::Vector3 start_position_, goal_position_;
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
rviz::VectorProperty * focus_point_property_
The point around which the camera "orbits".
An un-constrained "flying" camera, specified by an eye point, focus point, and up vector...
Ogre::Vector3 reference_position_
Used to store the position of the attached frame relative to <Fixed frame>="">
Ogre::Vector3 fixedFrameToAttachedLocal(const Ogre::Vector3 &v)
bool update(const T &new_val, T &my_val)
rviz::BoolProperty * mouse_enabled_property_
If True, most user changes to camera state are disabled.
bool dragging_
A flag indicating the dragging state of the mouse.
rviz::RosTopicProperty * camera_placement_publish_topic_property_
rviz::EditableEnumProperty * interaction_mode_property_
Select between Orbit or FPS control style.
rviz::RosTopicProperty * camera_placement_topic_property_
rviz::BoolProperty * fixed_up_property_
If True, "up" is fixed to ... up.
rviz::RosTopicProperty * mouse_point_publish_topic_property_
rviz::Shape * focal_shape_
A small ellipsoid to show the focus point.
Ogre::Quaternion reference_orientation_
Used to store the orientation of the attached frame relative to <Fixed frame>=""> ...
rviz::VectorProperty * eye_point_property_
The position of the camera.
QCursor interaction_disabled_cursor_
A cursor for indicating mouse interaction is disabled.
Ogre::Vector3 attachedLocalToFixedFrame(const Ogre::Vector3 &v)
rviz::FloatProperty * default_transition_time_property_
A default time for any animation requests.
rviz::VectorProperty * up_vector_property_
The up vector for the camera.
rviz::FloatProperty * distance_property_
The camera&#39;s distance from the focal point.


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Sat Mar 20 2021 03:03:18