Go to the documentation of this file.
38 #include <OgreViewport.h>
39 #include <OgreCamera.h>
40 #include <OgreSceneNode.h>
41 #include <Eigen/Geometry>
42 #include <QSignalBlocker>
47 Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Y) *
48 Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Z);
76 camera_->setProjectionType(Ogre::PT_PERSPECTIVE);
82 camera_->setPosition(Ogre::Vector3(5, 5, 10));
92 auto source_camera = source_view->
getCamera();
93 camera_->setPosition(source_camera->getPosition());
94 camera_->setOrientation(source_camera->getOrientation());
109 "<b>Left-Click:</b> Rotate Roll. <b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z.");
111 setStatus(
"<b>Left-Click:</b> Rotate Yaw/Pitch. <b>Shift Left-Click</b>: Rotate Roll. "
112 "<b>Middle-Click:</b> Move X/Y. <b>Right-Click:</b>: Move Z.");
117 if (event.
type == QEvent::MouseMove)
119 diff_x =
event.x -
event.last_x;
120 diff_y =
event.y -
event.last_y;
126 rotate(-diff_x * 0.005, diff_y * 0.005, 0.0
f);
131 int cx =
event.viewport->getActualWidth() / 2;
132 int cy =
event.viewport->getActualHeight() / 2;
134 float roll = atan2(event.
last_y - cy, event.
last_x - cx) - atan2(event.
y - cy, event.
x - cx);
135 if (std::isfinite(roll))
141 move(diff_x * 0.01, -diff_y * 0.01, 0.0
f);
143 else if (event.
right())
146 move(0.0
f, 0.0
f, diff_y * 0.1);
155 int diff =
event.wheel_delta;
156 move(0.0
f, 0.0
f, -diff * 0.01);
162 Eigen::Quaterniond q = Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()) *
163 Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY()) *
164 Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX());
172 Eigen::Quaterniond quat(q.w, q.x, q.y, q.z);
173 auto ypr = quat.toRotationMatrix().eulerAngles(2, 1, 0);
189 Eigen::Quaterniond quat(q.w, q.x, q.y, q.z);
190 auto ypr = quat.toRotationMatrix().eulerAngles(2, 1, 0);
195 const Ogre::Quaternion& )
202 Ogre::Vector3 translate(x, y, z);
217 QSignalBlocker block(prop);
221 if (
angle > Ogre::Math::PI)
222 angle = -Ogre::Math::PI + fmod(
angle, Ogre::Math::PI);
223 if (
angle < -Ogre::Math::PI)
224 angle = Ogre::Math::PI + fmod(
angle, Ogre::Math::PI);
Ogre::Vector3 reference_position_
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
FloatProperty * pitch_property_
The camera's pitch (rotation around the y-axis), in radians.
VectorProperty * position_property_
The camera's position.
void setPropertiesFromCamera()
set yaw, pitch, roll, position properties from camera
void move(float x, float y, float z)
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...
A first-person camera, controlled by yaw, pitch, roll, and position.
virtual void changedPosition()
static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION
void onTargetFrameChanged(const Ogre::Vector3 &old_reference_position, const Ogre::Quaternion &old_reference_orientation) override
Override to implement the change in properties which nullifies the change in target frame.
FloatProperty * yaw_property_
The camera's yaw (rotation around the z-axis), in radians.
DisplayContext * context_
Ogre::Quaternion getOrientation(float yaw, float pitch, float roll)
yield camera orientation for given Euler angles
Property specialized to enforce floating point max/min.
FloatProperty * roll_property_
The camera's roll (rotation around the x-axis), in radians.
void hide()
Hide this Property in any PropertyTreeWidgets.
void _rotate(FloatProperty *prop, float angle)
void onInitialize() override
Do subclass-specific initialization.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void onInitialize() override
Do subclass-specific initialization. Called by ViewController::initialize after context_ and camera_ ...
virtual float getFloat() const
virtual bool setVector(const Ogre::Vector3 &vector)
void handleMouseEvent(ViewportMouseEvent &event) override
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 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 rotate(float yaw, float pitch, float roll)
Ogre::Camera * getCamera() const
bool setFloat(float new_value)
Float-typed "SLOT" version of setValue().
void resetRoll()
zero roll angle
void setCursor(CursorType cursor_type)
virtual Ogre::Vector3 getVector() const
void setStatus(const QString &message)
virtual void changedOrientation()
bool add(const Ogre::Vector3 &offset)
Ogre::SceneNode * target_scene_node_
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09