diff --git a/rviz_rendering/CMakeLists.txt b/rviz_rendering/CMakeLists.txt index 9aede40d1..f6f9dee29 100644 --- a/rviz_rendering/CMakeLists.txt +++ b/rviz_rendering/CMakeLists.txt @@ -103,4 +103,16 @@ endif() install(TARGETS rendering_example DESTINATION bin) +if(BUILD_TESTING) + # TODO(wjwwood): replace this with ament_lint_auto() and/or add the copyright linter back + find_package(ament_cmake_cppcheck REQUIRED) + find_package(ament_cmake_cpplint REQUIRED) + find_package(ament_cmake_lint_cmake REQUIRED) + find_package(ament_cmake_uncrustify REQUIRED) + ament_cppcheck() + ament_cpplint() + ament_lint_cmake() + ament_uncrustify() +endif() + ament_package() diff --git a/rviz_rendering/package.xml b/rviz_rendering/package.xml index e28edd809..a57d4e142 100644 --- a/rviz_rendering/package.xml +++ b/rviz_rendering/package.xml @@ -22,6 +22,11 @@ rviz_ogre_vendor qtbase5-dev + ament_cppcheck + ament_cpplint + ament_cmake + ament_uncrustify + assimp libogre libqt5-core diff --git a/rviz_rendering/src/SdkQtCameraMan.h b/rviz_rendering/src/SdkQtCameraMan.h deleted file mode 100644 index 3463177e6..000000000 --- a/rviz_rendering/src/SdkQtCameraMan.h +++ /dev/null @@ -1,366 +0,0 @@ -/* - ----------------------------------------------------------------------------- - This source file is part of OGRE - (Object-oriented Graphics Rendering Engine) - For the latest info, see http://www.ogre3d.org/ - - Copyright (c) 2000-2014 Torus Knot Software Ltd - - Permission is hereby granted, free of charge, to any person obtaining a copy - of this software and associated documentation files (the "Software"), to deal - in the Software without restriction, including without limitation the rights - to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - - The above copyright notice and this permission notice shall be included in - all copies or substantial portions of the Software. - - THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - THE SOFTWARE. - ----------------------------------------------------------------------------- - */ -// File modified to change OIS to Qt KeyEvents -#ifndef __SdkQtCameraMan_H__ -#define __SdkQtCameraMan_H__ - -#include "OgreCamera.h" -#include "OgreSceneNode.h" -#include "OgreFrameListener.h" -#include -#include - -// enum CameraStyle should be in other namespace than OgreBites::CameraStyle -namespace OgreQtBites -{ - enum CameraStyle // enumerator values for different styles of camera movement - { - CS_FREELOOK, - CS_ORBIT, - CS_MANUAL - }; - - /*============================================================================= - | Utility class for controlling the camera in samples. - =============================================================================*/ - class SdkQtCameraMan - { - public: - SdkQtCameraMan(Ogre::Camera* cam) - : mCamera(0) - , mTarget(0) - , mOrbiting(false) - , mZooming(false) - , mTopSpeed(150) - , mVelocity(Ogre::Vector3::ZERO) - , mGoingForward(false) - , mGoingBack(false) - , mGoingLeft(false) - , mGoingRight(false) - , mGoingUp(false) - , mGoingDown(false) - , mFastMove(false) - { - - setCamera(cam); - setStyle(CS_FREELOOK); - } - - virtual ~SdkQtCameraMan() {} - - /*----------------------------------------------------------------------------- - | Swaps the camera on our camera man for another camera. - -----------------------------------------------------------------------------*/ - virtual void setCamera(Ogre::Camera* cam) - { - mCamera = cam; - } - - virtual Ogre::Camera* getCamera() - { - return mCamera; - } - - /*----------------------------------------------------------------------------- - | Sets the target we will revolve around. Only applies for orbit style. - -----------------------------------------------------------------------------*/ - virtual void setTarget(Ogre::SceneNode* target) - { - if (target != mTarget) - { - mTarget = target; - if(target) - { - setYawPitchDist(Ogre::Degree(0), Ogre::Degree(15), 150); - mCamera->setAutoTracking(true, mTarget); - } - else - { - mCamera->setAutoTracking(false); - } - - } - - - } - - virtual Ogre::SceneNode* getTarget() - { - return mTarget; - } - - /*----------------------------------------------------------------------------- - | Sets the spatial offset from the target. Only applies for orbit style. - -----------------------------------------------------------------------------*/ - virtual void setYawPitchDist(Ogre::Radian yaw, Ogre::Radian pitch, Ogre::Real dist) - { - mCamera->setPosition(mTarget->_getDerivedPosition()); - mCamera->setOrientation(mTarget->_getDerivedOrientation()); - mCamera->yaw(yaw); - mCamera->pitch(-pitch); - mCamera->moveRelative(Ogre::Vector3(0, 0, dist)); - } - - /*----------------------------------------------------------------------------- - | Sets the camera's top speed. Only applies for free-look style. - -----------------------------------------------------------------------------*/ - virtual void setTopSpeed(Ogre::Real topSpeed) - { - mTopSpeed = topSpeed; - } - - virtual Ogre::Real getTopSpeed() - { - return mTopSpeed; - } - - /*----------------------------------------------------------------------------- - | Sets the movement style of our camera man. - -----------------------------------------------------------------------------*/ - virtual void setStyle(CameraStyle style) - { - if (mStyle != CS_ORBIT && style == CS_ORBIT) - { - setTarget(mTarget ? mTarget : mCamera->getSceneManager()->getRootSceneNode()); - mCamera->setFixedYawAxis(true); - manualStop(); - setYawPitchDist(Ogre::Degree(0), Ogre::Degree(15), 150); - } - else if (mStyle != CS_FREELOOK && style == CS_FREELOOK) - { - mCamera->setAutoTracking(false); - mCamera->setFixedYawAxis(true); - } - else if (mStyle != CS_MANUAL && style == CS_MANUAL) - { - mCamera->setAutoTracking(false); - manualStop(); - } - mStyle = style; - - } - - virtual CameraStyle getStyle() - { - return mStyle; - } - - /*----------------------------------------------------------------------------- - | Manually stops the camera when in free-look mode. - -----------------------------------------------------------------------------*/ - virtual void manualStop() - { - if (mStyle == CS_FREELOOK) - { - mGoingForward = false; - mGoingBack = false; - mGoingLeft = false; - mGoingRight = false; - mGoingUp = false; - mGoingDown = false; - mVelocity = Ogre::Vector3::ZERO; - } - } - - virtual bool frameRenderingQueued(const Ogre::FrameEvent& evt) - { - if (mStyle == CS_FREELOOK) - { - // build our acceleration vector based on keyboard input composite - Ogre::Vector3 accel = Ogre::Vector3::ZERO; - if (mGoingForward) accel += mCamera->getDirection(); - if (mGoingBack) accel -= mCamera->getDirection(); - if (mGoingRight) accel += mCamera->getRight(); - if (mGoingLeft) accel -= mCamera->getRight(); - if (mGoingUp) accel += mCamera->getUp(); - if (mGoingDown) accel -= mCamera->getUp(); - - // if accelerating, try to reach top speed in a certain time - Ogre::Real topSpeed = mFastMove ? mTopSpeed * 20 : mTopSpeed; - if (accel.squaredLength() != 0) - { - accel.normalise(); - mVelocity += accel * topSpeed * evt.timeSinceLastFrame * 10; - } - // if not accelerating, try to stop in a certain time - else mVelocity -= mVelocity * evt.timeSinceLastFrame * 10; - - Ogre::Real tooSmall = std::numeric_limits::epsilon(); - - // keep camera velocity below top speed and above epsilon - if (mVelocity.squaredLength() > topSpeed * topSpeed) - { - mVelocity.normalise(); - mVelocity *= topSpeed; - } - else if (mVelocity.squaredLength() < tooSmall * tooSmall) - mVelocity = Ogre::Vector3::ZERO; - - if (mVelocity != Ogre::Vector3::ZERO) mCamera->move(mVelocity * evt.timeSinceLastFrame); - } - - return true; - } - - /*----------------------------------------------------------------------------- - | Processes key presses for free-look style movement. - -----------------------------------------------------------------------------*/ - virtual void injectKeyDown(const QKeyEvent& evt) - { - if (mStyle == CS_FREELOOK) - { - if (evt.key() == Qt::Key_W || evt.key() == Qt::Key_Up) mGoingForward = true; - else if (evt.key() == Qt::Key_S || evt.key() == Qt::Key_Down) mGoingBack = true; - else if (evt.key() == Qt::Key_A || evt.key() == Qt::Key_Left) mGoingLeft = true; - else if (evt.key() == Qt::Key_D || evt.key() == Qt::Key_Right) mGoingRight = true; - else if (evt.key() == Qt::Key_PageUp) mGoingUp = true; - else if (evt.key() == Qt::Key_PageDown) mGoingDown = true; - else if (evt.key() == Qt::Key_Shift) mFastMove = true; - } - } - - /*----------------------------------------------------------------------------- - | Processes key releases for free-look style movement. - -----------------------------------------------------------------------------*/ - virtual void injectKeyUp(const QKeyEvent& evt) - { - if (mStyle == CS_FREELOOK) - { - if (evt.key() == Qt::Key_W || evt.key() == Qt::Key_Up) mGoingForward = false; - else if (evt.key() == Qt::Key_S || evt.key() == Qt::Key_Down) mGoingBack = false; - else if (evt.key() == Qt::Key_A || evt.key() == Qt::Key_Left) mGoingLeft = false; - else if (evt.key() == Qt::Key_D || evt.key() == Qt::Key_Right) mGoingRight = false; - else if (evt.key() == Qt::Key_PageUp) mGoingUp = false; - else if (evt.key() == Qt::Key_PageDown) mGoingDown = false; - else if (evt.key() == Qt::Key_Shift) mFastMove = false; - } - } - - /*----------------------------------------------------------------------------- - | Processes mouse movement differently for each style. - -----------------------------------------------------------------------------*/ - virtual void injectMouseMove(int relX, int relY) - { -// static int lastX = evt.x(); -// static int lastY = evt.y(); -// int relX = evt.x() - lastX; -// int relY = evt.y() - lastY; -// lastX = evt.x(); -// lastY = evt.y(); - if (mStyle == CS_ORBIT) - { - Ogre::Real dist = (mCamera->getPosition() - mTarget->_getDerivedPosition()).length(); - - if (mOrbiting) // yaw around the target, and pitch locally - { - mCamera->setPosition(mTarget->_getDerivedPosition()); - - mCamera->yaw(Ogre::Degree(-relX * 0.025f)); - mCamera->pitch(Ogre::Degree(-relY * 0.025f)); - - mCamera->moveRelative(Ogre::Vector3(0, 0, dist)); - - // don't let the camera go over the top or around the bottom of the target - } - else if (mZooming) // move the camera toward or away from the target - { - // the further the camera is, the faster it moves - mCamera->moveRelative(Ogre::Vector3(0, 0, relY * 0.004f * dist)); - } - } - else if (mStyle == CS_FREELOOK) - { - mCamera->yaw(Ogre::Degree(-relX * 0.15f)); - mCamera->pitch(Ogre::Degree(-relY * 0.15f)); - } - } - - /*----------------------------------------------------------------------------- - | Processes mouse movement differently for each style. - -----------------------------------------------------------------------------*/ - virtual void injectWheelMove(const QWheelEvent& evt) - { - int relZ = evt.delta(); - if (mStyle == CS_ORBIT) - { - Ogre::Real dist = (mCamera->getPosition() - mTarget->_getDerivedPosition()).length(); - - if (relZ != 0) // move the camera toward or away from the target - { - // the further the camera is, the faster it moves - mCamera->moveRelative(Ogre::Vector3(0, 0, -relZ * 0.0008f * dist)); - } - } - } - - /*----------------------------------------------------------------------------- - | Processes mouse presses. Only applies for orbit style. - | Left button is for orbiting, and right button is for zooming. - -----------------------------------------------------------------------------*/ - virtual void injectMouseDown(const QMouseEvent& evt) - { - if (mStyle == CS_ORBIT) - { - if (evt.buttons() & Qt::LeftButton) mOrbiting = true; - else if (evt.buttons() & Qt::RightButton) mZooming = true; - } - } - - /*----------------------------------------------------------------------------- - | Processes mouse releases. Only applies for orbit style. - | Left button is for orbiting, and right button is for zooming. - -----------------------------------------------------------------------------*/ - virtual void injectMouseUp(const QMouseEvent& evt) - { - if (mStyle == CS_ORBIT) - { - if (evt.buttons() & Qt::LeftButton) mOrbiting = false; - else if (evt.buttons() & Qt::RightButton) mZooming = false; - } - } - - protected: - - Ogre::Camera* mCamera; - CameraStyle mStyle; - Ogre::SceneNode* mTarget; - bool mOrbiting; - bool mZooming; - Ogre::Real mTopSpeed; - Ogre::Vector3 mVelocity; - bool mGoingForward; - bool mGoingBack; - bool mGoingLeft; - bool mGoingRight; - bool mGoingUp; - bool mGoingDown; - bool mFastMove; - }; -} - -#endif \ No newline at end of file diff --git a/rviz_rendering/src/rviz_rendering/ogre_logging.cpp b/rviz_rendering/src/rviz_rendering/ogre_logging.cpp index d92a87b71..57f90d18b 100644 --- a/rviz_rendering/src/rviz_rendering/ogre_logging.cpp +++ b/rviz_rendering/src/rviz_rendering/ogre_logging.cpp @@ -115,6 +115,8 @@ void OgreLogging::configureLogging() static CustomOgreLogListener ll; Ogre::LogManager * log_manager = Ogre::LogManager::getSingletonPtr(); if (!log_manager) { + // suppressing this memleak warning from cppcheck below + // because this pointer is stored by Ogre internally log_manager = new Ogre::LogManager(); } Ogre::Log * l = log_manager->createLog(filename_, false, false, (preference_ == NoLogging)); @@ -124,6 +126,7 @@ void OgreLogging::configureLogging() if (preference_ == StandardOut) { ll.min_lml = Ogre::LML_NORMAL; } + // cppcheck-suppress memleak } } // namespace rviz_rendering diff --git a/rviz_rendering/src/rviz_rendering/render_window_impl.cpp b/rviz_rendering/src/rviz_rendering/render_window_impl.cpp index df30d9e23..15313c1d6 100644 --- a/rviz_rendering/src/rviz_rendering/render_window_impl.cpp +++ b/rviz_rendering/src/rviz_rendering/render_window_impl.cpp @@ -168,24 +168,6 @@ createScene(Ogre::SceneManager * ogre_scene_manager) light->setPosition(20.0f, 80.0f, 50.0f); } -class CustomOgreFrameListener : public Ogre::FrameListener -{ -public: - explicit CustomOgreFrameListener(OgreQtBites::SdkQtCameraMan * camera_man) - : camera_man_(camera_man) - {} - - virtual - bool - frameRenderingQueued(const Ogre::FrameEvent & evt) - { - camera_man_->frameRenderingQueued(evt); - return true; - } - - OgreQtBites::SdkQtCameraMan * camera_man_; -}; - void RenderWindowImpl::initialize() { @@ -201,11 +183,13 @@ RenderWindowImpl::initialize() ogre_scene_manager_ = ogre_root->createSceneManager(Ogre::ST_GENERIC); ogre_camera_ = ogre_scene_manager_->createCamera("MainCamera"); - ogre_camera_->setPosition(Ogre::Vector3(0.0f, 0.0f, 10.0f)); - ogre_camera_->lookAt(Ogre::Vector3(0.0f, 0.0f, -300.0f)); ogre_camera_->setNearClipDistance(0.1f); ogre_camera_->setFarClipDistance(200.0f); - camera_man_ = new OgreQtBites::SdkQtCameraMan(ogre_camera_); + + auto camera_node_ = ogre_scene_manager_->getRootSceneNode()->createChildSceneNode(); + ogre_camera_->setPosition(Ogre::Vector3(0.0f, 0.0f, 10.0f)); + ogre_camera_->lookAt(Ogre::Vector3(0.0f, 0.0f, -300.0f)); + camera_node_->attachObject(ogre_camera_); Ogre::Viewport * pViewPort = ogre_render_window_->addViewport(ogre_camera_); auto bg_color = Ogre::ColourValue(0.0f, 0.5f, 1.0f); @@ -219,9 +203,6 @@ RenderWindowImpl::initialize() Ogre::ResourceGroupManager::getSingleton().initialiseAllResourceGroups(); createScene(ogre_scene_manager_); - - ogre_frame_listener_ = new CustomOgreFrameListener(camera_man_); - ogre_root->addFrameListener(ogre_frame_listener_); } void diff --git a/rviz_rendering/src/rviz_rendering/render_window_impl.hpp b/rviz_rendering/src/rviz_rendering/render_window_impl.hpp index db6a3420a..b8723b4b4 100644 --- a/rviz_rendering/src/rviz_rendering/render_window_impl.hpp +++ b/rviz_rendering/src/rviz_rendering/render_window_impl.hpp @@ -50,8 +50,6 @@ #include #include -#include "../SdkQtCameraMan.h" - #ifndef _WIN32 # pragma GCC diagnostic pop #endif @@ -88,7 +86,6 @@ class RenderWindowImpl Ogre::FrameListener * ogre_frame_listener_; Ogre::SceneManager * ogre_scene_manager_; Ogre::Camera * ogre_camera_; - OgreQtBites::SdkQtCameraMan * camera_man_; bool animating_; };