|
| 1 | +// Copyright (c) 2012, Willow Garage, Inc. |
| 2 | +// Copyright (c) 2018, Bosch Software Innovations GmbH. |
| 3 | +// All rights reserved. |
| 4 | +// |
| 5 | +// Redistribution and use in source and binary forms, with or without |
| 6 | +// modification, are permitted provided that the following conditions are met: |
| 7 | +// |
| 8 | +// * Redistributions of source code must retain the above copyright |
| 9 | +// notice, this list of conditions and the following disclaimer. |
| 10 | +// |
| 11 | +// * Redistributions in binary form must reproduce the above copyright |
| 12 | +// notice, this list of conditions and the following disclaimer in the |
| 13 | +// documentation and/or other materials provided with the distribution. |
| 14 | +// |
| 15 | +// * Neither the name of the copyright holder nor the names of its |
| 16 | +// contributors may be used to endorse or promote products derived from |
| 17 | +// this software without specific prior written permission. |
| 18 | +// |
| 19 | +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" |
| 20 | +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE |
| 21 | +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE |
| 22 | +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE |
| 23 | +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR |
| 24 | +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF |
| 25 | +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS |
| 26 | +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN |
| 27 | +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) |
| 28 | +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
| 29 | +// POSSIBILITY OF SUCH DAMAGE. |
| 30 | + |
| 31 | + |
| 32 | +#include "rviz_default_plugins/view_controllers/frame/frame_view_controller.hpp" |
| 33 | + |
| 34 | +#include <cmath> |
| 35 | + |
| 36 | +#include <OgreCamera.h> |
| 37 | +#include <OgreQuaternion.h> |
| 38 | +#include <OgreSceneNode.h> |
| 39 | +#include <OgreSceneManager.h> |
| 40 | +#include <OgreVector.h> |
| 41 | +#include <OgreViewport.h> |
| 42 | + |
| 43 | +#include "rviz_rendering/geometry.hpp" |
| 44 | +#include "rviz_rendering/objects/shape.hpp" |
| 45 | + |
| 46 | +#include "rviz_common/display_context.hpp" |
| 47 | +#include "rviz_common/viewport_mouse_event.hpp" |
| 48 | +#include "rviz_common/uniform_string_stream.hpp" |
| 49 | + |
| 50 | +namespace rviz_default_plugins |
| 51 | +{ |
| 52 | +namespace view_controllers |
| 53 | +{ |
| 54 | +static const QString ANY_AXIS("arbitrary"); |
| 55 | + |
| 56 | +// helper function to create axis strings from option ID |
| 57 | +inline QString fmtAxis(int i) |
| 58 | +{ |
| 59 | + return QString("%1%2 axis").arg(QChar(i % 2 ? '+' : '-')).arg(QChar('x' + (i - 1) / 2)); |
| 60 | +} |
| 61 | + |
| 62 | +static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION = |
| 63 | + Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Y) * |
| 64 | + Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Z); |
| 65 | + |
| 66 | +static const float PITCH_LIMIT_LOW = -Ogre::Math::HALF_PI + 0.001f; |
| 67 | +static const float PITCH_LIMIT_HIGH = Ogre::Math::HALF_PI - 0.001f; |
| 68 | + |
| 69 | +static const Ogre::Vector3 DEFAULT_FPS_POSITION = Ogre::Vector3(5, 5, 10); |
| 70 | + |
| 71 | +FrameViewController::FrameViewController() |
| 72 | +{ |
| 73 | + axis_property_ = new rviz_common::properties::EnumProperty("Point towards", fmtAxis(6), |
| 74 | + "Point the camera along the given axis of the frame.", this, |
| 75 | + SLOT(changedAxis())); |
| 76 | + axis_property_->addOption(ANY_AXIS, -1); |
| 77 | + |
| 78 | + // x,y,z axes get integers from 1..6: +x, -x, +y, -y, +z, -z |
| 79 | + for (int i = 1; i <= 6; ++i) { |
| 80 | + axis_property_->addOption(fmtAxis(i), i); |
| 81 | + } |
| 82 | + previous_axis_ = axis_property_->getOptionInt(); |
| 83 | + |
| 84 | + locked_property_ = new rviz_common::properties::BoolProperty("Lock Camera", false, |
| 85 | + "Lock camera in its current pose relative to the frame", this); |
| 86 | +} |
| 87 | + |
| 88 | +void FrameViewController::onInitialize() |
| 89 | +{ |
| 90 | + FPSViewController::onInitialize(); |
| 91 | + changedAxis(); |
| 92 | +} |
| 93 | + |
| 94 | +int FrameViewController::actualCameraAxisOption(double precision) const |
| 95 | +{ |
| 96 | + // compare current camera direction with unit axes |
| 97 | + Ogre::Vector3 actual = |
| 98 | + (camera_scene_node_->getOrientation() * ROBOT_TO_CAMERA_ROTATION.Inverse()) * |
| 99 | + Ogre::Vector3::UNIT_X; |
| 100 | + for (unsigned int i = 0; i < 3; ++i) { |
| 101 | + Ogre::Vector3 axis(0, 0, 0); |
| 102 | + axis[i] = 1.0; |
| 103 | + auto scalar_product = axis.dotProduct(actual); |
| 104 | + if (std::abs(scalar_product) > 1.0 - precision) { |
| 105 | + return 1 + 2 * i + (scalar_product > 0 ? 0 : 1); |
| 106 | + } |
| 107 | + } |
| 108 | + return -1; |
| 109 | +} |
| 110 | + |
| 111 | +void FrameViewController::setAxisFromCamera() |
| 112 | +{ |
| 113 | + int actual = actualCameraAxisOption(); |
| 114 | + if (axis_property_->getOptionInt() == actual) { // no change? |
| 115 | + return; |
| 116 | + } |
| 117 | + |
| 118 | + QSignalBlocker block(axis_property_); |
| 119 | + axis_property_->setString(actual == -1 ? ANY_AXIS : fmtAxis(actual)); |
| 120 | + rememberAxis(actual); |
| 121 | +} |
| 122 | + |
| 123 | +void FrameViewController::changedAxis() |
| 124 | +{ |
| 125 | + rememberAxis(axis_property_->getOptionInt()); |
| 126 | + reset(); |
| 127 | +} |
| 128 | + |
| 129 | +inline void FrameViewController::rememberAxis(int current) |
| 130 | +{ |
| 131 | + if (current >= 1) { // remember previous axis selection |
| 132 | + previous_axis_ = current; |
| 133 | + } |
| 134 | +} |
| 135 | + |
| 136 | +void FrameViewController::reset() |
| 137 | +{ |
| 138 | + camera_scene_node_->setPosition(Ogre::Vector3::ZERO); |
| 139 | + Ogre::Vector3 axis(0, 0, 0); |
| 140 | + int option = previous_axis_; |
| 141 | + if (option >= 1 && option <= 6) { |
| 142 | + axis[(option - 1) / 2] = (option % 2) ? +1 : -1; |
| 143 | + Ogre::Quaternion q; |
| 144 | + if (option == 2) { // special case for the -X axis |
| 145 | + // Create a rotation of 180 degrees around the Z axis |
| 146 | + q = Ogre::Quaternion(Ogre::Radian(Ogre::Math::PI), Ogre::Vector3::UNIT_Z); |
| 147 | + } else { |
| 148 | + q = Ogre::Vector3::UNIT_X.getRotationTo(axis); |
| 149 | + } |
| 150 | + camera_scene_node_->setOrientation(q * ROBOT_TO_CAMERA_ROTATION); |
| 151 | + } |
| 152 | + setPropertiesFromCamera(camera_); |
| 153 | +} |
| 154 | + |
| 155 | +void FrameViewController::handleMouseEvent(rviz_common::ViewportMouseEvent & event) |
| 156 | +{ |
| 157 | + if (locked_property_->getBool()) { |
| 158 | + setStatus("Unlock camera in settings to enable mouse interaction."); |
| 159 | + return; |
| 160 | + } |
| 161 | + FPSViewController::handleMouseEvent(event); |
| 162 | +} |
| 163 | + |
| 164 | +void FrameViewController::onTargetFrameChanged( |
| 165 | + const Ogre::Vector3 & /*old_reference_position*/, |
| 166 | + const Ogre::Quaternion & /*old_reference_orientation*/) |
| 167 | +{ |
| 168 | + // don't adapt the camera pose to the old reference position, but just jump to new frame |
| 169 | +} |
| 170 | + |
| 171 | +} // namespace view_controllers |
| 172 | +} // namespace rviz_default_plugins |
| 173 | + |
| 174 | +#include <pluginlib/class_list_macros.hpp> // NOLINT(build/include_order) |
| 175 | +PLUGINLIB_EXPORT_CLASS( |
| 176 | + rviz_default_plugins::view_controllers::FrameViewController, rviz_common::ViewController) |
0 commit comments