33 #ifndef JSK_RVIZ_PLUGINS_TABLET_VIEW_CONTROLLER_H_ 34 #define JSK_RVIZ_PLUGINS_TABLET_VIEW_CONTROLLER_H_ 42 #include "view_controller_msgs/CameraPlacement.h" 44 #include <OGRE/OgreVector3.h> 45 #include <OGRE/OgreQuaternion.h> 54 class QuaternionProperty;
55 class TfFrameProperty;
56 class EditableEnumProperty;
57 class RosTopicProperty;
69 enum { TRANSITION_LINEAR = 0,
70 TRANSITION_SPHERICAL};
79 virtual void onInitialize();
84 virtual void onActivate();
88 void move_focus_and_eye(
float x,
float y,
float z );
91 void move_eye(
float x,
float y,
float z );
96 void yaw_pitch_roll(
float yaw,
float pitch,
float roll );
104 virtual void lookAt(
const Ogre::Vector3& point );
108 void orbitCameraTo(
const Ogre::Vector3& point);
111 void moveEyeWithFocusTo(
const Ogre::Vector3& point);
114 virtual void reset();
139 virtual void updateAttachedFrame();
142 virtual void onDistancePropertyChanged();
145 virtual void onFocusPropertyChanged();
148 virtual void onEyePropertyChanged();
151 virtual void onUpPropertyChanged();
157 virtual void update(
float dt,
float ros_dt);
160 void connectPositionProperties();
163 void disconnectPositionProperties();
168 virtual void onAttachedFrameChanged(
const Ogre::Vector3& old_reference_position,
const Ogre::Quaternion& old_reference_orientation );
172 void updateAttachedSceneNode();
174 void cameraPlacementCallback(
const view_controller_msgs::CameraPlacementConstPtr &cp_ptr);
176 void transformCameraPlacementToAttachedFrame(view_controller_msgs::CameraPlacement &cp);
180 void setPropertiesFromCamera( Ogre::Camera* source_camera );
183 void beginNewTransition(
const Ogre::Vector3 &eye,
const Ogre::Vector3 &focus,
const Ogre::Vector3 &up,
187 void cancelTransition();
195 float getDistanceFromCameraToFocalPoint();
197 void publishCurrentPlacement();
199 Ogre::Quaternion getOrientation();
203 void updatePublishTopics();
204 void updateMousePointPublishTopics();
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::SceneNode * attached_scene_node_
Ogre::Vector3 reference_position_
Used to store the position of the attached frame relative to <Fixed frame>="">
ros::Duration current_transition_duration_
rviz::TfFrameProperty * attached_frame_property_
Ogre::Vector3 fixedFrameToAttachedLocal(const Ogre::Vector3 &v)
bool update(const T &new_val, T &my_val)
ros::Subscriber placement_subscriber_
rviz::BoolProperty * mouse_enabled_property_
If True, most user changes to camera state are disabled.
ros::Time transition_start_time_
ros::Publisher mouse_point_publisher_
ros::Publisher placement_publisher_
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.
ros::Time trajectory_start_time_
Ogre::Vector3 start_focus_
rviz::RosTopicProperty * mouse_point_publish_topic_property_
rviz::Shape * focal_shape_
A small ellipsoid to show the focus point.
Ogre::Vector3 start_position_
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's distance from the focal point.