Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 #ifndef JSK_RVIZ_PLUGINS_TABLET_VIEW_CONTROLLER_H_
00034 #define JSK_RVIZ_PLUGINS_TABLET_VIEW_CONTROLLER_H_
00035 
00036 #ifndef Q_MOC_RUN
00037 #include "rviz/view_controller.h"
00038 
00039 #include <ros/subscriber.h>
00040 #include <ros/ros.h>
00041 
00042 #include "view_controller_msgs/CameraPlacement.h"
00043 
00044 #include <OGRE/OgreVector3.h>
00045 #include <OGRE/OgreQuaternion.h>
00046 #endif
00047 
00048 namespace rviz {
00049   class SceneNode;
00050   class Shape;
00051   class BoolProperty;
00052   class FloatProperty;
00053   class VectorProperty;
00054   class QuaternionProperty;
00055   class TfFrameProperty;
00056   class EditableEnumProperty;
00057   class RosTopicProperty;
00058 }
00059 
00060 namespace jsk_rviz_plugins
00061 {
00062 
00064 class TabletViewController : public rviz::ViewController
00065 {
00066 Q_OBJECT
00067 public:
00068 
00069   enum { TRANSITION_LINEAR = 0,
00070          TRANSITION_SPHERICAL};
00071 
00072   TabletViewController();
00073   virtual ~TabletViewController();
00074 
00079   virtual void onInitialize();
00080 
00084   virtual void onActivate();
00085 
00086 
00088   void move_focus_and_eye( float x, float y, float z );
00089 
00091   void move_eye( float x, float y, float z );
00092 
00093 
00096   void yaw_pitch_roll( float yaw, float pitch, float roll );
00097 
00098 
00099   virtual void handleMouseEvent(rviz::ViewportMouseEvent& evt);
00100 
00101 
00104   virtual void lookAt( const Ogre::Vector3& point );
00105 
00106 
00108   void orbitCameraTo( const Ogre::Vector3& point);
00109 
00111   void moveEyeWithFocusTo( const Ogre::Vector3& point);
00112 
00114   virtual void reset();
00115 
00121   virtual void mimic( ViewController* source_view );
00122 
00130   virtual void transitionFrom( ViewController* previous_view );
00131 
00132 
00133 protected Q_SLOTS:
00139   virtual void updateAttachedFrame();
00140   
00142   virtual void onDistancePropertyChanged();
00143 
00145   virtual void onFocusPropertyChanged();
00146   
00148   virtual void onEyePropertyChanged();
00149 
00151   virtual void onUpPropertyChanged();
00152 
00153 protected:  
00154 
00157   virtual void update(float dt, float ros_dt);
00158 
00160   void connectPositionProperties();
00161 
00163   void disconnectPositionProperties();
00164 
00168   virtual void onAttachedFrameChanged( const Ogre::Vector3& old_reference_position, const Ogre::Quaternion& old_reference_orientation );
00169 
00172   void updateAttachedSceneNode();
00173 
00174   void cameraPlacementCallback(const view_controller_msgs::CameraPlacementConstPtr &cp_ptr);
00175   
00176   void transformCameraPlacementToAttachedFrame(view_controller_msgs::CameraPlacement &cp);
00177 
00178   
00179 
00180   void setPropertiesFromCamera( Ogre::Camera* source_camera );
00181 
00183   void beginNewTransition(const Ogre::Vector3 &eye, const Ogre::Vector3 &focus, const Ogre::Vector3 &up,
00184                           const ros::Duration &transition_time);
00185 
00187   void cancelTransition();
00188 
00190   void updateCamera();
00191 
00192   Ogre::Vector3 fixedFrameToAttachedLocal(const Ogre::Vector3 &v) { return reference_orientation_.Inverse()*(v - reference_position_); }
00193   Ogre::Vector3 attachedLocalToFixedFrame(const Ogre::Vector3 &v) { return reference_position_ + (reference_orientation_*v); }
00194 
00195   float getDistanceFromCameraToFocalPoint(); 
00196 
00197   void publishCurrentPlacement();
00198   void publishMouseEvent(rviz::ViewportMouseEvent& event);
00199   Ogre::Quaternion getOrientation(); 
00200 
00201 protected Q_SLOTS:
00202   void updateTopics();
00203   void updatePublishTopics();
00204   void updateMousePointPublishTopics();
00205 protected:    
00206 
00207   ros::NodeHandle nh_;
00208 
00209   rviz::BoolProperty* mouse_enabled_property_;            
00210   rviz::EditableEnumProperty* interaction_mode_property_; 
00211   rviz::BoolProperty* fixed_up_property_;                 
00212 
00213   rviz::FloatProperty* distance_property_;                
00214   rviz::VectorProperty* eye_point_property_;              
00215   rviz::VectorProperty* focus_point_property_;            
00216   rviz::VectorProperty* up_vector_property_;              
00217   rviz::FloatProperty* default_transition_time_property_; 
00218 
00219   rviz::RosTopicProperty* camera_placement_topic_property_;
00220   rviz::RosTopicProperty* camera_placement_publish_topic_property_;
00221   rviz::RosTopicProperty* mouse_point_publish_topic_property_;
00222 
00223 
00224   rviz::TfFrameProperty* attached_frame_property_;
00225   Ogre::SceneNode* attached_scene_node_;
00226 
00227   Ogre::Quaternion reference_orientation_;    
00228   Ogre::Vector3 reference_position_;          
00229 
00230   
00231   bool animate_;
00232   Ogre::Vector3 start_position_, goal_position_;
00233   Ogre::Vector3 start_focus_, goal_focus_;
00234   Ogre::Vector3 start_up_, goal_up_;
00235   ros::Time trajectory_start_time_;
00236   ros::Time transition_start_time_;
00237   ros::Duration current_transition_duration_;
00238 
00239   rviz::Shape* focal_shape_;    
00240   bool dragging_;         
00241 
00242   QCursor interaction_disabled_cursor_;         
00243   
00244 
00245   ros::Subscriber placement_subscriber_;
00246 
00247   ros::Publisher placement_publisher_;
00248   
00249   ros::Publisher mouse_point_publisher_;
00250 };
00251 
00252 }  
00253 
00254 #endif // RVIZ_ANIMATED_VIEW_CONTROLLER_H