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 #include "view_controller.h"
00031 #include "viewport_mouse_event.h"
00032 #include "visualization_manager.h"
00033 #include "frame_manager.h"
00034
00035 #include <OGRE/OgreCamera.h>
00036 #include <OGRE/OgreSceneNode.h>
00037 #include <OGRE/OgreSceneManager.h>
00038
00039 namespace rviz
00040 {
00041
00042 ViewController::ViewController(VisualizationManager* manager, const std::string& name)
00043 : manager_(manager)
00044 , camera_(0)
00045 , name_(name)
00046 {
00047 reference_node_ = manager_->getSceneManager()->getRootSceneNode()->createChildSceneNode();
00048 }
00049
00050 ViewController::~ViewController()
00051 {
00052 manager_->getSceneManager()->destroySceneNode(reference_node_);
00053 }
00054
00055 void ViewController::activate(Ogre::Camera* camera, const std::string& reference_frame)
00056 {
00057 camera_ = camera;
00058 reference_frame_ = reference_frame;
00059 updateReferenceNode();
00060
00061 onActivate();
00062 }
00063
00064 void ViewController::deactivate()
00065 {
00066 onDeactivate();
00067
00068 camera_ = 0;
00069 }
00070
00071 void ViewController::update(float dt, float ros_dt)
00072 {
00073 updateReferenceNode();
00074 onUpdate(dt, ros_dt);
00075 }
00076
00077 void ViewController::setReferenceFrame(const std::string& reference_frame)
00078 {
00079 Ogre::Vector3 old_pos = reference_node_->getPosition();
00080 Ogre::Quaternion old_orient = reference_node_->getOrientation();
00081 reference_frame_ = reference_frame;
00082 updateReferenceNode();
00083
00084 onReferenceFrameChanged(old_pos, old_orient);
00085 }
00086
00087 void ViewController::updateReferenceNode()
00088 {
00089 Ogre::Vector3 old_position = reference_node_->getPosition();
00090 Ogre::Quaternion old_orientation = reference_node_->getOrientation();
00091 Ogre::Vector3 position;
00092 Ogre::Quaternion orientation;
00093 if (FrameManager::instance()->getTransform(reference_frame_, ros::Time(), position, orientation, true))
00094 {
00095 reference_node_->setPosition(position);
00096 reference_node_->setOrientation(orientation);
00097
00098 if (!old_position.positionEquals(position, 0.01) ||
00099 !old_orientation.equals(orientation, Ogre::Radian(0.05)))
00100 {
00101 manager_->queueRender();
00102 }
00103 }
00104 }
00105
00106 }