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 #include "rviz/view_controller.h"
00037
00038 #include <ros/subscriber.h>
00039 #include <ros/ros.h>
00040
00041 #include "view_controller_msgs/CameraPlacement.h"
00042
00043 #include <OGRE/OgreVector3.h>
00044 #include <OGRE/OgreQuaternion.h>
00045
00046 namespace rviz {
00047 class SceneNode;
00048 class Shape;
00049 class BoolProperty;
00050 class FloatProperty;
00051 class VectorProperty;
00052 class QuaternionProperty;
00053 class TfFrameProperty;
00054 class EditableEnumProperty;
00055 class RosTopicProperty;
00056 }
00057
00058 namespace jsk_rviz_plugins
00059 {
00060
00062 class TabletViewController : public rviz::ViewController
00063 {
00064 Q_OBJECT
00065 public:
00066
00067 enum { TRANSITION_LINEAR = 0,
00068 TRANSITION_SPHERICAL};
00069
00070 TabletViewController();
00071 virtual ~TabletViewController();
00072
00077 virtual void onInitialize();
00078
00082 virtual void onActivate();
00083
00084
00086 void move_focus_and_eye( float x, float y, float z );
00087
00089 void move_eye( float x, float y, float z );
00090
00091
00094 void yaw_pitch_roll( float yaw, float pitch, float roll );
00095
00096
00097 virtual void handleMouseEvent(rviz::ViewportMouseEvent& evt);
00098
00099
00102 virtual void lookAt( const Ogre::Vector3& point );
00103
00104
00106 void orbitCameraTo( const Ogre::Vector3& point);
00107
00109 void moveEyeWithFocusTo( const Ogre::Vector3& point);
00110
00112 virtual void reset();
00113
00119 virtual void mimic( ViewController* source_view );
00120
00128 virtual void transitionFrom( ViewController* previous_view );
00129
00130
00131 protected Q_SLOTS:
00137 virtual void updateAttachedFrame();
00138
00140 virtual void onDistancePropertyChanged();
00141
00143 virtual void onFocusPropertyChanged();
00144
00146 virtual void onEyePropertyChanged();
00147
00149 virtual void onUpPropertyChanged();
00150
00151 protected:
00152
00155 virtual void update(float dt, float ros_dt);
00156
00158 void connectPositionProperties();
00159
00161 void disconnectPositionProperties();
00162
00166 virtual void onAttachedFrameChanged( const Ogre::Vector3& old_reference_position, const Ogre::Quaternion& old_reference_orientation );
00167
00170 void updateAttachedSceneNode();
00171
00172 void cameraPlacementCallback(const view_controller_msgs::CameraPlacementConstPtr &cp_ptr);
00173
00174 void transformCameraPlacementToAttachedFrame(view_controller_msgs::CameraPlacement &cp);
00175
00176
00177
00178 void setPropertiesFromCamera( Ogre::Camera* source_camera );
00179
00181 void beginNewTransition(const Ogre::Vector3 &eye, const Ogre::Vector3 &focus, const Ogre::Vector3 &up,
00182 const ros::Duration &transition_time);
00183
00185 void cancelTransition();
00186
00188 void updateCamera();
00189
00190 Ogre::Vector3 fixedFrameToAttachedLocal(const Ogre::Vector3 &v) { return reference_orientation_.Inverse()*(v - reference_position_); }
00191 Ogre::Vector3 attachedLocalToFixedFrame(const Ogre::Vector3 &v) { return reference_position_ + (reference_orientation_*v); }
00192
00193 float getDistanceFromCameraToFocalPoint();
00194
00195 void publishCurrentPlacement();
00196 void publishMouseEvent(rviz::ViewportMouseEvent& event);
00197 Ogre::Quaternion getOrientation();
00198
00199 protected Q_SLOTS:
00200 void updateTopics();
00201 void updatePublishTopics();
00202 void updateMousePointPublishTopics();
00203 protected:
00204
00205 ros::NodeHandle nh_;
00206
00207 rviz::BoolProperty* mouse_enabled_property_;
00208 rviz::EditableEnumProperty* interaction_mode_property_;
00209 rviz::BoolProperty* fixed_up_property_;
00210
00211 rviz::FloatProperty* distance_property_;
00212 rviz::VectorProperty* eye_point_property_;
00213 rviz::VectorProperty* focus_point_property_;
00214 rviz::VectorProperty* up_vector_property_;
00215 rviz::FloatProperty* default_transition_time_property_;
00216
00217 rviz::RosTopicProperty* camera_placement_topic_property_;
00218 rviz::RosTopicProperty* camera_placement_publish_topic_property_;
00219 rviz::RosTopicProperty* mouse_point_publish_topic_property_;
00220
00221
00222 rviz::TfFrameProperty* attached_frame_property_;
00223 Ogre::SceneNode* attached_scene_node_;
00224
00225 Ogre::Quaternion reference_orientation_;
00226 Ogre::Vector3 reference_position_;
00227
00228
00229 bool animate_;
00230 Ogre::Vector3 start_position_, goal_position_;
00231 Ogre::Vector3 start_focus_, goal_focus_;
00232 Ogre::Vector3 start_up_, goal_up_;
00233 ros::Time trajectory_start_time_;
00234 ros::Time transition_start_time_;
00235 ros::Duration current_transition_duration_;
00236
00237 rviz::Shape* focal_shape_;
00238 bool dragging_;
00239
00240 QCursor interaction_disabled_cursor_;
00241
00242
00243 ros::Subscriber placement_subscriber_;
00244
00245 ros::Publisher placement_publisher_;
00246
00247 ros::Publisher mouse_point_publisher_;
00248 };
00249
00250 }
00251
00252 #endif // RVIZ_ANIMATED_VIEW_CONTROLLER_H