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 #ifndef RVIZ_ANIMATED_VIEW_CONTROLLER_H
00033 #define RVIZ_ANIMATED_VIEW_CONTROLLER_H
00034
00035 #include "rviz/view_controller.h"
00036
00037 #include <ros/subscriber.h>
00038 #include <ros/ros.h>
00039
00040 #include "view_controller_msgs/CameraPlacement.h"
00041
00042 #include <OGRE/OgreVector3.h>
00043 #include <OGRE/OgreQuaternion.h>
00044
00045 namespace rviz {
00046 class SceneNode;
00047 class Shape;
00048 class BoolProperty;
00049 class FloatProperty;
00050 class VectorProperty;
00051 class QuaternionProperty;
00052 class TfFrameProperty;
00053 class EditableEnumProperty;
00054 class RosTopicProperty;
00055 }
00056
00057 namespace rviz_animated_view_controller
00058 {
00059
00061 class AnimatedViewController : public rviz::ViewController
00062 {
00063 Q_OBJECT
00064 public:
00065
00066 enum { TRANSITION_LINEAR = 0,
00067 TRANSITION_SPHERICAL};
00068
00069 AnimatedViewController();
00070 virtual ~AnimatedViewController();
00071
00076 virtual void onInitialize();
00077
00081 virtual void onActivate();
00082
00083
00085 void move_focus_and_eye( float x, float y, float z );
00086
00088 void move_eye( float x, float y, float z );
00089
00090
00093 void yaw_pitch_roll( float yaw, float pitch, float roll );
00094
00095
00096 virtual void handleMouseEvent(rviz::ViewportMouseEvent& evt);
00097
00098
00101 virtual void lookAt( const Ogre::Vector3& point );
00102
00103
00105 void orbitCameraTo( const Ogre::Vector3& point);
00106
00108 void moveEyeWithFocusTo( const Ogre::Vector3& point);
00109
00111 virtual void reset();
00112
00118 virtual void mimic( ViewController* source_view );
00119
00127 virtual void transitionFrom( ViewController* previous_view );
00128
00129
00130 protected Q_SLOTS:
00136 virtual void updateAttachedFrame();
00137
00139 virtual void onDistancePropertyChanged();
00140
00142 virtual void onFocusPropertyChanged();
00143
00145 virtual void onEyePropertyChanged();
00146
00148 virtual void onUpPropertyChanged();
00149
00150 protected:
00151
00154 virtual void update(float dt, float ros_dt);
00155
00157 void connectPositionProperties();
00158
00160 void disconnectPositionProperties();
00161
00165 virtual void onAttachedFrameChanged( const Ogre::Vector3& old_reference_position, const Ogre::Quaternion& old_reference_orientation );
00166
00169 void updateAttachedSceneNode();
00170
00171 void cameraPlacementCallback(const view_controller_msgs::CameraPlacementConstPtr &cp_ptr);
00172
00173 void transformCameraPlacementToAttachedFrame(view_controller_msgs::CameraPlacement &cp);
00174
00175
00176
00177 void setPropertiesFromCamera( Ogre::Camera* source_camera );
00178
00180 void beginNewTransition(const Ogre::Vector3 &eye, const Ogre::Vector3 &focus, const Ogre::Vector3 &up,
00181 const ros::Duration &transition_time);
00182
00184 void cancelTransition();
00185
00187 void updateCamera();
00188
00189 Ogre::Vector3 fixedFrameToAttachedLocal(const Ogre::Vector3 &v) { return reference_orientation_.Inverse()*(v - reference_position_); }
00190 Ogre::Vector3 attachedLocalToFixedFrame(const Ogre::Vector3 &v) { return reference_position_ + (reference_orientation_*v); }
00191
00192 float getDistanceFromCameraToFocalPoint();
00193
00194 Ogre::Quaternion getOrientation();
00195
00196 protected Q_SLOTS:
00197 void updateTopics();
00198
00199
00200 protected:
00201
00202 ros::NodeHandle nh_;
00203
00204 rviz::BoolProperty* mouse_enabled_property_;
00205 rviz::EditableEnumProperty* interaction_mode_property_;
00206 rviz::BoolProperty* fixed_up_property_;
00207
00208 rviz::FloatProperty* distance_property_;
00209 rviz::VectorProperty* eye_point_property_;
00210 rviz::VectorProperty* focus_point_property_;
00211 rviz::VectorProperty* up_vector_property_;
00212 rviz::FloatProperty* default_transition_time_property_;
00213
00214 rviz::RosTopicProperty* camera_placement_topic_property_;
00215
00216
00217 rviz::TfFrameProperty* attached_frame_property_;
00218 Ogre::SceneNode* attached_scene_node_;
00219
00220 Ogre::Quaternion reference_orientation_;
00221 Ogre::Vector3 reference_position_;
00222
00223
00224 bool animate_;
00225 Ogre::Vector3 start_position_, goal_position_;
00226 Ogre::Vector3 start_focus_, goal_focus_;
00227 Ogre::Vector3 start_up_, goal_up_;
00228 ros::Time trajectory_start_time_;
00229 ros::Time transition_start_time_;
00230 ros::Duration current_transition_duration_;
00231
00232 rviz::Shape* focal_shape_;
00233 bool dragging_;
00234
00235 QCursor interaction_disabled_cursor_;
00236
00237
00238 ros::Subscriber placement_subscriber_;
00239
00240 };
00241
00242 }
00243
00244 #endif // RVIZ_ANIMATED_VIEW_CONTROLLER_H