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 "fixed_orientation_ortho_view_controller.h"
00031 #include "rviz/viewport_mouse_event.h"
00032 #include "rviz/visualization_manager.h"
00033
00034 #include <OGRE/OgreCamera.h>
00035 #include <OGRE/OgreSceneManager.h>
00036 #include <OGRE/OgreSceneNode.h>
00037 #include <OGRE/OgreVector3.h>
00038 #include <OGRE/OgreQuaternion.h>
00039 #include <OGRE/OgreViewport.h>
00040
00041 #include <ogre_tools/shape.h>
00042 #include <ogre_tools/orthographic.h>
00043
00044 #include <stdint.h>
00045 #include <sstream>
00046
00047 namespace rviz
00048 {
00049
00050 FixedOrientationOrthoViewController::FixedOrientationOrthoViewController(VisualizationManager* manager, const std::string& name, Ogre::SceneNode* target_scene_node)
00051 : ViewController(manager, name, target_scene_node)
00052 , scale_(10.0f)
00053 , orientation_(Ogre::Quaternion::IDENTITY)
00054 {
00055 }
00056
00057 FixedOrientationOrthoViewController::~FixedOrientationOrthoViewController()
00058 {
00059 }
00060
00061 void FixedOrientationOrthoViewController::handleMouseEvent(ViewportMouseEvent& event)
00062 {
00063 bool moved = false;
00064
00065 if ( event.event.Dragging() )
00066 {
00067 int32_t diff_x = event.event.GetX() - event.last_x;
00068 int32_t diff_y = event.event.GetY() - event.last_y;
00069
00070 if ( event.event.LeftIsDown() && !event.event.ShiftDown() )
00071 {
00072 camera_->roll( Ogre::Radian( -diff_x * 0.005 ) );
00073 orientation_ = camera_->getOrientation();
00074 }
00075 else if ( event.event.MiddleIsDown() ||
00076 ( event.event.ShiftDown() && event.event.LeftIsDown() ))
00077 {
00078 move( -diff_x / scale_, diff_y / scale_, 0.0f );
00079 }
00080 else if ( event.event.RightIsDown() )
00081 {
00082 scale_ *= 1.0 - diff_y * 0.01;
00083 }
00084
00085 moved = true;
00086 }
00087
00088 if ( event.event.GetWheelRotation() != 0 )
00089 {
00090 int diff = event.event.GetWheelRotation();
00091 scale_ *= 1.0 - (-diff) * 0.001;
00092
00093 moved = true;
00094 }
00095
00096 if (moved)
00097 {
00098 manager_->queueRender();
00099 }
00100 }
00101
00102 void FixedOrientationOrthoViewController::setOrientation(const Ogre::Quaternion& orientation)
00103 {
00104 orientation_ = orientation;
00105 }
00106
00107 void FixedOrientationOrthoViewController::onActivate()
00108 {
00109 camera_->setProjectionType(Ogre::PT_ORTHOGRAPHIC);
00110 camera_->setFixedYawAxis(false);
00111 camera_->setDirection(target_scene_node_->getOrientation() * Ogre::Vector3::UNIT_X);
00112 }
00113
00114 void FixedOrientationOrthoViewController::onDeactivate()
00115 {
00116 camera_->setCustomProjectionMatrix(false);
00117 }
00118
00119 void FixedOrientationOrthoViewController::onUpdate(float dt, float ros_dt)
00120 {
00121 updateCamera();
00122 }
00123
00124 void FixedOrientationOrthoViewController::lookAt( const Ogre::Vector3& point )
00125 {
00126 Ogre::Vector3 reference_point = target_scene_node_->getPosition() - point;
00127 Ogre::Vector3 current_pos = camera_->getPosition();
00128 current_pos.x = reference_point.x;
00129 current_pos.z = reference_point.z;
00130
00131 camera_->setPosition(current_pos);
00132 }
00133
00134 void FixedOrientationOrthoViewController::onTargetFrameChanged(const Ogre::Vector3& old_reference_position, const Ogre::Quaternion& old_reference_orientation)
00135 {
00136 lookAt(target_scene_node_->getPosition());
00137 }
00138
00139 void FixedOrientationOrthoViewController::updateCamera()
00140 {
00141 camera_->setOrientation(orientation_);
00142
00143 float width = camera_->getViewport()->getActualWidth();
00144 float height = camera_->getViewport()->getActualHeight();
00145
00146 Ogre::Matrix4 proj;
00147 ogre_tools::buildScaledOrthoMatrix( proj, -width / scale_ / 2, width / scale_ / 2, -height / scale_ / 2, height / scale_ / 2,
00148 camera_->getNearClipDistance(), camera_->getFarClipDistance() );
00149 camera_->setCustomProjectionMatrix(true, proj);
00150 }
00151
00152 void FixedOrientationOrthoViewController::move( float x, float y, float z )
00153 {
00154 camera_->moveRelative( Ogre::Vector3( x, y, z ) );
00155 }
00156
00157 void FixedOrientationOrthoViewController::fromString(const std::string& str)
00158 {
00159 std::istringstream iss(str);
00160
00161 iss >> scale_;
00162 iss.ignore();
00163
00164 Ogre::Vector3 vec;
00165 iss >> vec.x;
00166 iss.ignore();
00167 iss >> vec.y;
00168 iss.ignore();
00169 iss >> vec.z;
00170 iss.ignore();
00171 camera_->setPosition(vec);
00172
00173 Ogre::Quaternion quat;
00174 iss >> quat.x;
00175 iss.ignore();
00176 iss >> quat.y;
00177 iss.ignore();
00178 iss >> quat.z;
00179 iss.ignore();
00180 iss >> quat.w;
00181 iss.ignore();
00182 orientation_ = quat;
00183
00184 resetTargetSceneNodePosition();
00185 }
00186
00187 std::string FixedOrientationOrthoViewController::toString()
00188 {
00189 std::ostringstream oss;
00190 oss << scale_ << " " << camera_->getPosition().x << " " << camera_->getPosition().y << " " << camera_->getPosition().z
00191 << " " << camera_->getOrientation().x << " " << camera_->getOrientation().y << " " << camera_->getOrientation().z << " " << camera_->getOrientation().w;
00192
00193 return oss.str();
00194 }
00195
00196
00197 }