49 #include "view_controller_msgs/CameraPlacement.h"
50 #include "geometry_msgs/PointStamped.h"
52 #include <OGRE/OgreViewport.h>
53 #include <OGRE/OgreQuaternion.h>
54 #include <OGRE/OgreVector3.h>
55 #include <OGRE/OgreSceneNode.h>
56 #include <OGRE/OgreSceneManager.h>
57 #include <OGRE/OgreCamera.h>
62 #include <OGRE/OgreRenderWindow.h>
66 using namespace view_controller_msgs;
81 static inline Ogre::Vector3
vectorFromMsg(
const geometry_msgs::Point &m) {
return Ogre::Vector3(m.x, m.y, m.z); }
82 static inline Ogre::Vector3
vectorFromMsg(
const geometry_msgs::Vector3 &m) {
return Ogre::Vector3(m.x, m.y, m.z); }
85 geometry_msgs::Point m;
86 m.x = o.x; m.y = o.y; m.z = o.z;
89 static inline void pointOgreToMsg(
const Ogre::Vector3 &o, geometry_msgs::Point &m) { m.x = o.x; m.y = o.y; m.z = o.z; }
93 geometry_msgs::Vector3 m;
94 m.x = o.x; m.y = o.y; m.z = o.z;
97 static inline void vectorOgreToMsg(
const Ogre::Vector3 &o, geometry_msgs::Vector3 &m) { m.x = o.x; m.y = o.y; m.z = o.z; }
103 : nh_(
""), animate_(false), dragging_( false )
108 "Enables mouse control of the camera.",
111 "Select the style of mouse interaction.",
118 "If enabled, the camera is not allowed to roll side-to-side.",
122 "TF frame the camera is attached to.",
125 "Position of the camera.",
this );
127 "Position of the focus/orbit point.",
this );
129 "The vector which maps to \"up\" in the camera image plane.",
this );
131 "The distance between the camera position and the focus point.",
135 "The default time to use for camera transitions.",
138 QString::fromStdString(ros::message_traits::datatype<view_controller_msgs::CameraPlacement>() ),
139 "Topic for CameraPlacement messages",
this, SLOT(
updateTopics()));
142 QString::fromStdString(ros::message_traits::datatype<view_controller_msgs::CameraPlacement>() ),
146 QString::fromStdString(ros::message_traits::datatype<geometry_msgs::PointStamped>() ),
174 geometry_msgs::PointStamped
msg;
180 msg.point.x = (double)event.
x / window->getWidth();
181 msg.point.y = (double)event.
y / window->getHeight();
188 view_controller_msgs::CameraPlacement
msg;
193 msg.eye.header.stamp =
now;
194 msg.eye.header.frame_id = fixed_frame;
196 msg.eye.point.x = eye[0];
197 msg.eye.point.y = eye[1];
198 msg.eye.point.z = eye[2];
200 msg.focus.header.stamp =
now;
201 msg.focus.header.frame_id = fixed_frame;
203 msg.focus.point.x = focus[0];
204 msg.focus.point.y = focus[1];
205 msg.focus.point.z = focus[2];
207 msg.up.header.stamp =
now;
208 msg.up.header.frame_id = fixed_frame;
210 msg.up.vector.x = up[0];
211 msg.up.vector.y = up[1];
212 msg.up.vector.z = up[2];
234 camera_->setProjectionType( Ogre::PT_PERSPECTIVE );
309 camera_->setFixedYawAxis(
false);
326 Ogre::Vector3 new_reference_position;
327 Ogre::Quaternion new_reference_orientation;
331 new_reference_position, new_reference_orientation ))
391 setStatus(
"<b>Mouse interaction is disabled. You can enable it by checking the \"Mouse Enabled\" check-box in the Views panel." );
394 else if ( event.
shift() )
396 setStatus(
"TODO: Fix me! <b>Left-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z." );
400 setStatus(
"TODO: Fix me! <b>Left-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z." );
404 setStatus(
"TODO: Fix me! <b>Left-Click:</b> Rotate. <b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Zoom. <b>Shift</b>: More options." );
406 if (event.
type == QEvent::MouseButtonPress
407 || event.
type == QEvent::MouseButtonRelease
416 if( event.
type == QEvent::MouseButtonPress )
423 else if( event.
type == QEvent::MouseButtonRelease )
431 diff_x =
event.x -
event.last_x;
432 diff_y =
event.y -
event.last_y;
448 float fovY =
camera_->getFOVy().valueRadians();
449 float fovX = 2.0f * atan( tan( fovY / 2.0
f ) *
camera_->getAspectRatio() );
455 ((
float)diff_y / (
float)
height) * distance * tan( fovY / 2.0
f ) * 2.0
f,
463 else if( event.
right() )
473 move_eye( 0, 0, diff_y * 0.01 * distance );
483 int diff =
event.wheel_delta;
495 move_eye( 0, 0, -diff * 0.001 * distance );
528 Ogre::Vector3 direction = source_camera->getOrientation() * Ogre::Vector3::NEGATIVE_UNIT_Z;
548 Ogre::Camera* source_camera = source_view->
getCamera();
549 Ogre::Vector3 position = source_camera->getPosition();
550 Ogre::Quaternion orientation = source_camera->getOrientation();
552 if( source_view->
getClassId() ==
"rviz/Orbit" )
621 CameraPlacement cp = *cp_ptr;
626 if(cp.mouse_interaction_mode != cp.NO_CHANGE)
628 std::string name =
"";
629 if(cp.mouse_interaction_mode == cp.ORBIT) name =
MODE_ORBIT;
630 else if(cp.mouse_interaction_mode == cp.FPS) name =
MODE_FPS;
634 if(cp.target_frame !=
"")
640 if(cp.time_from_start.toSec() >= 0)
692 Ogre::Vector3 position_fixed_eye, position_fixed_focus, position_fixed_up;
693 Ogre::Quaternion rotation_fixed_eye, rotation_fixed_focus, rotation_fixed_up;
765 float progress = 0.5*(1-cos(fraction*M_PI));
796 Ogre::Quaternion old_camera_orientation =
camera_->getOrientation();
797 Ogre::Radian old_pitch = old_camera_orientation.getPitch(
false);
801 Ogre::Quaternion yaw_quat, pitch_quat, roll_quat;
802 yaw_quat.FromAngleAxis( Ogre::Radian( yaw ), Ogre::Vector3::UNIT_Y );
803 pitch_quat.FromAngleAxis( Ogre::Radian( pitch ), Ogre::Vector3::UNIT_X );
804 roll_quat.FromAngleAxis( Ogre::Radian( roll ), Ogre::Vector3::UNIT_Z );
805 Ogre::Quaternion orientation_change = yaw_quat * pitch_quat * roll_quat;
806 Ogre::Quaternion new_camera_orientation = old_camera_orientation * orientation_change;
807 Ogre::Radian new_pitch = new_camera_orientation.getPitch(
false);
812 orientation_change = yaw_quat * roll_quat;
813 new_camera_orientation = old_camera_orientation * orientation_change;
820 camera_->setOrientation( new_camera_orientation );
826 camera_->setPosition(new_eye_position);
838 return camera_->getOrientation();
843 Ogre::Vector3 translate(
x,
y,
z );
850 Ogre::Vector3 translate(
x,
y,
z );