38 #include <OgreViewport.h> 39 #include <OgreCamera.h> 40 #include <OgreSceneNode.h> 41 #include <Eigen/Geometry> 42 #include <QSignalBlocker> 46 static const QString
ANY_AXIS(
"arbitrary");
49 Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Y) *
50 Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Z);
55 return QStringLiteral(
"%1%2 axis").arg(QChar(i % 2 ?
'+' :
'-')).arg(QChar(
'x' + (i - 1) / 2));
63 "Point the camera along the given axis of the frame.",
this,
67 for (
int i = 1; i <= 6; ++i)
90 "Lock camera in its current pose relative to the frame",
this);
96 camera_->setProjectionType(Ogre::PT_PERSPECTIVE);
103 camera_->setPosition(Ogre::Vector3::ZERO);
104 Eigen::Vector3d axis(0, 0, 0);
106 if (option >= 1 && option <= 6)
108 axis[(option - 1) / 2] = (option % 2) ? +1 : -1;
109 Eigen::Quaterniond q = Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d::UnitX(), axis);
110 camera_->setOrientation(Ogre::Quaternion(q.w(), q.x(), q.y(), q.z()) * ROBOT_TO_CAMERA_ROTATION);
118 auto source_camera = source_view->
getCamera();
119 camera_->setPosition(source_camera->getPosition());
120 camera_->setOrientation(source_camera->getOrientation());
134 setStatus(
"Unlock camera in settings to enable mouse interaction.");
138 setStatus(
"<b>Left-Click:</b> Rotate Yaw/Pitch. <b>Shift Left-Click</b>: Rotate Roll. " 139 "<b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z.");
144 if (event.
type == QEvent::MouseMove)
146 diff_x =
event.x -
event.last_x;
147 diff_y =
event.y -
event.last_y;
150 if (event.
left() && !
event.shift())
153 rotate(-diff_x * 0.005, diff_y * 0.005, 0.0
f);
155 else if (event.
left() &&
event.shift())
158 int cx =
event.viewport->getActualWidth() / 2;
159 int cy =
event.viewport->getActualHeight() / 2;
162 if (std::isfinite(roll))
168 move(diff_x * 0.01, -diff_y * 0.01, 0.0
f);
170 else if (event.
right())
173 move(0.0
f, 0.0
f, diff_y * 0.1);
182 int diff =
event.wheel_delta;
183 move(0.0
f, 0.0
f, -diff * 0.01);
189 Eigen::Quaterniond q = Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()) *
190 Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY()) *
191 Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX());
193 return Ogre::Quaternion(q.w(), q.x(), q.y(), q.z()) * ROBOT_TO_CAMERA_ROTATION;
198 Ogre::Quaternion q =
camera_->getOrientation() * ROBOT_TO_CAMERA_ROTATION.Inverse();
199 Eigen::Quaterniond quat(q.w, q.x, q.y, q.z);
200 auto ypr = quat.toRotationMatrix().eulerAngles(2, 1, 0);
216 Ogre::Vector3 actual =
217 (
camera_->getOrientation() * ROBOT_TO_CAMERA_ROTATION.Inverse()) * Ogre::Vector3::UNIT_X;
218 for (
unsigned int i = 0; i < 3; ++i)
220 Ogre::Vector3 axis(0, 0, 0);
222 auto scalar_product = axis.dotProduct(actual);
223 if (std::abs(scalar_product) > 1.0 - precision)
224 return 1 + 2 * i + (scalar_product > 0 ? 0 : 1);
242 Ogre::Vector3 translate(x, y, z);
257 QSignalBlocker block(prop);
258 angle = fmod(prop->
getFloat() + angle, Ogre::Math::TWO_PI);
261 if (angle > Ogre::Math::PI)
262 angle = -Ogre::Math::PI + fmod(angle, Ogre::Math::PI);
263 if (angle < -Ogre::Math::PI)
264 angle = Ogre::Math::PI + fmod(angle, Ogre::Math::PI);
298 const Ogre::Quaternion& )
int actualCameraAxisOption(double precision=0.001) const
find enum ID from camera's current pose
virtual bool setVector(const Ogre::Vector3 &vector)
BoolProperty * locked_property_
Lock camera, i.e. disable mouse interaction?
void move(float x, float y, float z)
void rotate(float yaw, float pitch, float roll)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
void setCursor(CursorType cursor_type)
Ogre::Camera * getCamera() const
virtual Ogre::Vector3 getVector() const
FloatProperty * pitch_property_
The camera's pitch (rotation around the y-axis), in radians.
Property specialized to enforce floating point max/min.
Ogre::Quaternion getOrientation(float yaw, float pitch, float roll)
void changedOrientation()
bool add(const Ogre::Vector3 &offset)
void onInitialize() override
Do subclass-specific initialization.
VectorProperty * position_property_
The camera's position.
void updateTargetSceneNode() override
Update the position of the target_scene_node_ from the TF frame specified in the Target Frame propert...
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
Ogre::Vector3 reference_position_
FloatProperty * roll_property_
The camera's roll (rotation around the x-axis), in radians.
virtual void addOption(const QString &option, int value=0)
FloatProperty * yaw_property_
The camera's yaw (rotation around the z-axis), in radians.
void handleMouseEvent(ViewportMouseEvent &event) override
void rememberAxis(int current)
void setStatus(const QString &message)
Ogre::Quaternion reference_orientation_
void _rotate(FloatProperty *prop, float angle)
void setPropertiesFromCamera()
set yaw, pitch, roll, position properties from camera
EnumProperty * axis_property_
The axis that the camera aligns to.
void mimic(ViewController *source_view) override
Configure the settings of this view controller to give, as much as possible, a similar view as that g...
void onInitialize() override
Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ ...
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
A camera tied to a given frame.
Property specialized to provide getter for booleans.
virtual float getFloat() const
void onTargetFrameChanged(const Ogre::Vector3 &, const Ogre::Quaternion &) override
Override to implement the change in properties which nullifies the change in target frame...
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
Ogre::SceneNode * target_scene_node_
void lookAt(const Ogre::Vector3 &point) override
This should be implemented in each subclass to aim the camera at the given point in space (relative t...
void mimic(ViewController *source_view) override
Configure the settings of this view controller to give, as much as possible, a similar view as that g...
void hide()
Hide this Property in any PropertyTreeWidgets.
virtual bool getBool() const
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
DisplayContext * context_
void setAxisFromCamera()
set axis_property_ from camera
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION
virtual void setString(const QString &str)
Set the value of this property to the given string. Does not force the value to be one of the list of...
static const QString ANY_AXIS("arbitrary")