From e2c7c5ddae508d3e7b5aadb05d32027978a211af Mon Sep 17 00:00:00 2001 From: William Woodall Date: Wed, 30 Aug 2017 15:44:43 -0700 Subject: [PATCH 1/4] moving camera related h/cpp files from ogre_helpers --- .../include/rviz_rendering/camera_base.hpp | 0 .../object.h => rviz_rendering/include/rviz_rendering/object.hpp | 0 .../include/rviz_rendering/orbit_camera.hpp | 0 .../shape.h => rviz_rendering/include/rviz_rendering/shape.hpp | 0 .../src/rviz_rendering}/camera_base.cpp | 0 .../ogre_helpers => rviz_rendering/src/rviz_rendering}/object.cpp | 0 .../src/rviz_rendering}/orbit_camera.cpp | 0 .../ogre_helpers => rviz_rendering/src/rviz_rendering}/shape.cpp | 0 8 files changed, 0 insertions(+), 0 deletions(-) rename rviz/src/rviz/ogre_helpers/camera_base.h => rviz_rendering/include/rviz_rendering/camera_base.hpp (100%) rename rviz/src/rviz/ogre_helpers/object.h => rviz_rendering/include/rviz_rendering/object.hpp (100%) rename rviz/src/rviz/ogre_helpers/orbit_camera.h => rviz_rendering/include/rviz_rendering/orbit_camera.hpp (100%) rename rviz/src/rviz/ogre_helpers/shape.h => rviz_rendering/include/rviz_rendering/shape.hpp (100%) rename {rviz/src/rviz/ogre_helpers => rviz_rendering/src/rviz_rendering}/camera_base.cpp (100%) rename {rviz/src/rviz/ogre_helpers => rviz_rendering/src/rviz_rendering}/object.cpp (100%) rename {rviz/src/rviz/ogre_helpers => rviz_rendering/src/rviz_rendering}/orbit_camera.cpp (100%) rename {rviz/src/rviz/ogre_helpers => rviz_rendering/src/rviz_rendering}/shape.cpp (100%) diff --git a/rviz/src/rviz/ogre_helpers/camera_base.h b/rviz_rendering/include/rviz_rendering/camera_base.hpp similarity index 100% rename from rviz/src/rviz/ogre_helpers/camera_base.h rename to rviz_rendering/include/rviz_rendering/camera_base.hpp diff --git a/rviz/src/rviz/ogre_helpers/object.h b/rviz_rendering/include/rviz_rendering/object.hpp similarity index 100% rename from rviz/src/rviz/ogre_helpers/object.h rename to rviz_rendering/include/rviz_rendering/object.hpp diff --git a/rviz/src/rviz/ogre_helpers/orbit_camera.h b/rviz_rendering/include/rviz_rendering/orbit_camera.hpp similarity index 100% rename from rviz/src/rviz/ogre_helpers/orbit_camera.h rename to rviz_rendering/include/rviz_rendering/orbit_camera.hpp diff --git a/rviz/src/rviz/ogre_helpers/shape.h b/rviz_rendering/include/rviz_rendering/shape.hpp similarity index 100% rename from rviz/src/rviz/ogre_helpers/shape.h rename to rviz_rendering/include/rviz_rendering/shape.hpp diff --git a/rviz/src/rviz/ogre_helpers/camera_base.cpp b/rviz_rendering/src/rviz_rendering/camera_base.cpp similarity index 100% rename from rviz/src/rviz/ogre_helpers/camera_base.cpp rename to rviz_rendering/src/rviz_rendering/camera_base.cpp diff --git a/rviz/src/rviz/ogre_helpers/object.cpp b/rviz_rendering/src/rviz_rendering/object.cpp similarity index 100% rename from rviz/src/rviz/ogre_helpers/object.cpp rename to rviz_rendering/src/rviz_rendering/object.cpp diff --git a/rviz/src/rviz/ogre_helpers/orbit_camera.cpp b/rviz_rendering/src/rviz_rendering/orbit_camera.cpp similarity index 100% rename from rviz/src/rviz/ogre_helpers/orbit_camera.cpp rename to rviz_rendering/src/rviz_rendering/orbit_camera.cpp diff --git a/rviz/src/rviz/ogre_helpers/shape.cpp b/rviz_rendering/src/rviz_rendering/shape.cpp similarity index 100% rename from rviz/src/rviz/ogre_helpers/shape.cpp rename to rviz_rendering/src/rviz_rendering/shape.cpp From 3d971589d62283f61a76353b826dd418da150516 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Wed, 30 Aug 2017 15:51:20 -0700 Subject: [PATCH 2/4] first uncrustify pass on moved files --- .../include/rviz_rendering/camera_base.hpp | 60 +++--- .../include/rviz_rendering/object.hpp | 18 +- .../include/rviz_rendering/orbit_camera.hpp | 63 ++++--- .../include/rviz_rendering/shape.hpp | 38 ++-- .../src/rviz_rendering/camera_base.cpp | 20 +- rviz_rendering/src/rviz_rendering/object.cpp | 4 +- .../src/rviz_rendering/orbit_camera.cpp | 175 ++++++++---------- rviz_rendering/src/rviz_rendering/shape.cpp | 136 +++++++------- 8 files changed, 251 insertions(+), 263 deletions(-) diff --git a/rviz_rendering/include/rviz_rendering/camera_base.hpp b/rviz_rendering/include/rviz_rendering/camera_base.hpp index c310cab85..44088b66f 100644 --- a/rviz_rendering/include/rviz_rendering/camera_base.hpp +++ b/rviz_rendering/include/rviz_rendering/camera_base.hpp @@ -35,9 +35,9 @@ namespace Ogre { - class Camera; - class SceneNode; - class SceneManager; +class Camera; +class SceneNode; +class SceneManager; } namespace rviz @@ -57,20 +57,20 @@ class CameraBase * \brief Constructor * @param scene_manager Scene manager this camera is displaying */ - CameraBase( Ogre::SceneManager* scene_manager ); + CameraBase(Ogre::SceneManager * scene_manager); virtual ~CameraBase(); /** * \brief Get the Ogre camera associated with this camera object * @return The Ogre camera associated with this camera object */ - Ogre::Camera* getOgreCamera() { return camera_; } + Ogre::Camera * getOgreCamera() {return camera_; } /** * \brief Set a scene node that all camera transformations should be relative to * @param node The node */ - void setRelativeNode( Ogre::SceneNode* node ); + void setRelativeNode(Ogre::SceneNode * node); /** * \brief Called when the relative node changes */ @@ -81,11 +81,11 @@ class CameraBase /** * \brief Set the position of the camera */ - virtual void setPosition( const Ogre::Vector3& position ); + virtual void setPosition(const Ogre::Vector3 & position); /** * \brief Set the orientation of the camera */ - virtual void setOrientation( const Ogre::Quaternion& orientation ); + virtual void setOrientation(const Ogre::Quaternion & orientation); /** * \brief Yaw the camera. @@ -99,7 +99,7 @@ class CameraBase * * @param angle Angle to yaw, in radians */ - virtual void yaw( float angle ) = 0; + virtual void yaw(float angle) = 0; /** * \brief Pitch the camera. * @@ -112,7 +112,7 @@ class CameraBase * * @param angle Angle to pitch, in radians */ - virtual void pitch( float angle ) = 0; + virtual void pitch(float angle) = 0; /** * \brief Roll the camera. * @@ -125,23 +125,23 @@ class CameraBase * * @param angle Angle to roll, in radians */ - virtual void roll( float angle ) = 0; + virtual void roll(float angle) = 0; /** * \brief Set the orientation of the camera from a quaternion */ - virtual void setOrientation( float x, float y, float z, float w ) = 0; + virtual void setOrientation(float x, float y, float z, float w) = 0; /** * \brief Set the position of the camera */ - virtual void setPosition( float x, float y, float z ) = 0; + virtual void setPosition(float x, float y, float z) = 0; /** * \brief Set the position/orientation of this camera from another camera. * * @param camera The camera to set from */ - virtual void setFrom( CameraBase* camera ) = 0; + virtual void setFrom(CameraBase * camera) = 0; /** * \brief Get the position of this camera @@ -158,7 +158,7 @@ class CameraBase * \brief Point the camera at the specified point * @param point The point to look at */ - virtual void lookAt( const Ogre::Vector3& point ) = 0; + virtual void lookAt(const Ogre::Vector3 & point) = 0; /** * \brief Move the camera relative to its orientation @@ -167,14 +167,14 @@ class CameraBase * @param y Distance to move along the Y-axis * @param z Distance to move along the Z-axis */ - virtual void move( float x, float y, float z ) = 0; + virtual void move(float x, float y, float z) = 0; - virtual void mouseLeftDown( int x, int y ) {} - virtual void mouseMiddleDown( int x, int y ) {} - virtual void mouseRightDown( int x, int y ) {} - virtual void mouseLeftUp( int x, int y ) {} - virtual void mouseMiddleUp( int x, int y ) {} - virtual void mouseRightUp( int x, int y ) {} + virtual void mouseLeftDown(int x, int y) {} + virtual void mouseMiddleDown(int x, int y) {} + virtual void mouseRightDown(int x, int y) {} + virtual void mouseLeftUp(int x, int y) {} + virtual void mouseMiddleUp(int x, int y) {} + virtual void mouseRightUp(int x, int y) {} /** * \brief Handle a left mouse button drag @@ -182,44 +182,44 @@ class CameraBase * @param diff_x Pixels the mouse has moved in the (window space) x direction * @param diff_y Pixels the mouse has moved in the (window space) y direction */ - virtual void mouseLeftDrag( int diff_x, int diff_y, bool ctrl, bool alt, bool shift ) = 0; + virtual void mouseLeftDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift) = 0; /** * \brief Handle a middle mouse button drag * * @param diff_x Pixels the mouse has moved in the (window space) x direction * @param diff_y Pixels the mouse has moved in the (window space) y direction */ - virtual void mouseMiddleDrag( int diff_x, int diff_y, bool ctrl, bool alt, bool shift ) = 0; + virtual void mouseMiddleDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift) = 0; /** * \brief Handle a right mouse button drag * * @param diff_x Pixels the mouse has moved in the (window space) x direction * @param diff_y Pixels the mouse has moved in the (window space) y direction */ - virtual void mouseRightDrag( int diff_x, int diff_y, bool ctrl, bool alt, bool shift ) = 0; + virtual void mouseRightDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift) = 0; /** * \brief Handle a scrollwheel change * * @param diff Number of "units" the scrollwheel has moved * @todo Probably need to pass in how many units there are in a "click" of the wheel */ - virtual void scrollWheel( int diff, bool ctrl, bool alt, bool shift ) = 0; + virtual void scrollWheel(int diff, bool ctrl, bool alt, bool shift) = 0; /** * \brief Loads the camera's configure from the supplied string (generated through toString()) * @param str The string to load from */ - virtual void fromString(const std::string& str) = 0; + virtual void fromString(const std::string & str) = 0; /** * \brief Returns a string representation of the camera's configuration */ virtual std::string toString() = 0; protected: - Ogre::Camera* camera_; ///< Ogre camera associated with this camera object - Ogre::SceneManager* scene_manager_; ///< Scene manager this camera is part of + Ogre::Camera * camera_; ///< Ogre camera associated with this camera object + Ogre::SceneManager * scene_manager_; ///< Scene manager this camera is part of - Ogre::SceneNode* relative_node_; + Ogre::SceneNode * relative_node_; }; } // namespace rviz diff --git a/rviz_rendering/include/rviz_rendering/object.hpp b/rviz_rendering/include/rviz_rendering/object.hpp index 0391ac0dd..92eff3998 100644 --- a/rviz_rendering/include/rviz_rendering/object.hpp +++ b/rviz_rendering/include/rviz_rendering/object.hpp @@ -53,26 +53,26 @@ class Object * * @param scene_manager The scene manager this object should be part of. */ - Object( Ogre::SceneManager* scene_manager ); + Object(Ogre::SceneManager * scene_manager); virtual ~Object() {} /** * \brief Set the position of this object * @param Position vector position to set to. */ - virtual void setPosition( const Ogre::Vector3& position ) = 0; + virtual void setPosition(const Ogre::Vector3 & position) = 0; /** * \brief Set the orientation of the object * @param Orientation quaternion orientation to set to. */ - virtual void setOrientation( const Ogre::Quaternion& orientation ) = 0; + virtual void setOrientation(const Ogre::Quaternion & orientation) = 0; /** * \brief Set the scale of the object. Always relative to the identity orientation of the object. * @param Scale vector scale to set to. */ - virtual void setScale( const Ogre::Vector3& scale ) = 0; + virtual void setScale(const Ogre::Vector3 & scale) = 0; /** * \brief Set the color of the object. Values are in the range [0, 1] @@ -80,27 +80,27 @@ class Object * @param g Green component * @param b Blue component */ - virtual void setColor( float r, float g, float b, float a ) = 0; + virtual void setColor(float r, float g, float b, float a) = 0; /** * \brief Get the local position of this object * @return The position */ - virtual const Ogre::Vector3& getPosition() = 0; + virtual const Ogre::Vector3 & getPosition() = 0; /** * \brief Get the local orientation of this object * @return The orientation */ - virtual const Ogre::Quaternion& getOrientation() = 0; + virtual const Ogre::Quaternion & getOrientation() = 0; /** * \brief Set the user data on this object * @param data */ - virtual void setUserData( const Ogre::Any& data ) = 0; + virtual void setUserData(const Ogre::Any & data) = 0; protected: - Ogre::SceneManager* scene_manager_; ///< Ogre scene manager this object is part of + Ogre::SceneManager * scene_manager_; ///< Ogre scene manager this object is part of }; } // namespace rviz diff --git a/rviz_rendering/include/rviz_rendering/orbit_camera.hpp b/rviz_rendering/include/rviz_rendering/orbit_camera.hpp index ee760bc76..4b9ba7401 100644 --- a/rviz_rendering/include/rviz_rendering/orbit_camera.hpp +++ b/rviz_rendering/include/rviz_rendering/orbit_camera.hpp @@ -35,9 +35,9 @@ namespace Ogre { - class Camera; - class SceneNode; - class SceneManager; +class Camera; +class SceneNode; +class SceneManager; } namespace rviz @@ -62,67 +62,66 @@ class Shape; class OrbitCamera : public CameraBase { public: - OrbitCamera( Ogre::SceneManager* scene_manager ); + OrbitCamera(Ogre::SceneManager * scene_manager); virtual ~OrbitCamera(); /** * \brief Move in/out from the focal point, ie. adjust #distance_ by amount * @param amount The distance to move. Positive amount moves towards the focal point, negative moves away */ - void zoom( float amount ); + void zoom(float amount); /** * \brief Set the focal point of the camera. Keeps the pitch/yaw/distance the same * @param focal_point The new focal point */ - void setFocalPoint( const Ogre::Vector3& focal_point ); + void setFocalPoint(const Ogre::Vector3 & focal_point); - float getPitch() { return pitch_; } - float getYaw() { return yaw_; } - float getDistance() { return distance_; } - const Ogre::Vector3& getFocalPoint() { return focal_point_; } + float getPitch() {return pitch_; } + float getYaw() {return yaw_; } + float getDistance() {return distance_; } + const Ogre::Vector3 & getFocalPoint() {return focal_point_; } - virtual void setFrom( CameraBase* camera ); - virtual void yaw( float angle ); - virtual void pitch( float angle ); - virtual void roll( float angle ); - virtual void setOrientation( float x, float y, float z, float w ); - virtual void setPosition( float x, float y, float z ); - virtual void move( float x, float y, float z ); + virtual void setFrom(CameraBase * camera); + virtual void yaw(float angle); + virtual void pitch(float angle); + virtual void roll(float angle); + virtual void setOrientation(float x, float y, float z, float w); + virtual void setPosition(float x, float y, float z); + virtual void move(float x, float y, float z); virtual Ogre::Vector3 getPosition(); virtual Ogre::Quaternion getOrientation(); - virtual void lookAt( const Ogre::Vector3& point ); + virtual void lookAt(const Ogre::Vector3 & point); - virtual void mouseLeftDrag( int diff_x, int diff_y, bool ctrl, bool alt, bool shift ); - virtual void mouseMiddleDrag( int diff_x, int diff_y, bool ctrl, bool alt, bool shift ); - virtual void mouseRightDrag( int diff_x, int diff_y, bool ctrl, bool alt, bool shift ); - virtual void scrollWheel( int diff, bool ctrl, bool alt, bool shift ); + virtual void mouseLeftDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift); + virtual void mouseMiddleDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift); + virtual void mouseRightDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift); + virtual void scrollWheel(int diff, bool ctrl, bool alt, bool shift); /** * \brief Calculates the camera's position and orientation from the yaw, pitch, distance and focal point */ virtual void update(); - virtual void mouseLeftDown( int x, int y ); - virtual void mouseMiddleDown( int x, int y ); - virtual void mouseRightDown( int x, int y ); - virtual void mouseLeftUp( int x, int y ); - virtual void mouseMiddleUp( int x, int y ); - virtual void mouseRightUp( int x, int y ); + virtual void mouseLeftDown(int x, int y); + virtual void mouseMiddleDown(int x, int y); + virtual void mouseRightDown(int x, int y); + virtual void mouseLeftUp(int x, int y); + virtual void mouseMiddleUp(int x, int y); + virtual void mouseRightUp(int x, int y); - virtual void fromString(const std::string& str); + virtual void fromString(const std::string & str); virtual std::string toString(); private: - Ogre::Vector3 getGlobalFocalPoint(); /** * \brief Calculates pitch and yaw values given a new position and the current focal point * @param position Position to calculate the pitch/yaw for */ - void calculatePitchYawFromPosition( const Ogre::Vector3& position ); + void calculatePitchYawFromPosition(const Ogre::Vector3 & position); /** * \brief Normalizes the camera's pitch, preventing it from reaching vertical (or turning upside down) */ @@ -137,7 +136,7 @@ class OrbitCamera : public CameraBase float pitch_; ///< The camera's pitch (rotation around the x-axis), in radians float distance_; ///< The camera's distance from the focal point - Shape* focal_point_object_; + Shape * focal_point_object_; }; } // namespace rviz diff --git a/rviz_rendering/include/rviz_rendering/shape.hpp b/rviz_rendering/include/rviz_rendering/shape.hpp index bf4cae2bd..5f62faa25 100644 --- a/rviz_rendering/include/rviz_rendering/shape.hpp +++ b/rviz_rendering/include/rviz_rendering/shape.hpp @@ -67,10 +67,10 @@ class Shape : public Object * @param scene_manager The scene manager this object is associated with * @param parent_node A scene node to use as the parent of this object. If NULL, uses the root scene node. */ - Shape(Type shape_type, Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node = NULL); + Shape(Type shape_type, Ogre::SceneManager * scene_manager, Ogre::SceneNode * parent_node = NULL); virtual ~Shape(); - Type getType() { return type_; } + Type getType() {return type_; } /** * \brief Set the offset for this shape @@ -79,38 +79,39 @@ class Shape : public Object * * @param offset Amount to offset the center of the object from the pivot point */ - void setOffset( const Ogre::Vector3& offset ); + void setOffset(const Ogre::Vector3 & offset); - virtual void setColor( float r, float g, float b, float a ); - void setColor( const Ogre::ColourValue& c ); - virtual void setPosition( const Ogre::Vector3& position ); - virtual void setOrientation( const Ogre::Quaternion& orientation ); - virtual void setScale( const Ogre::Vector3& scale ); - virtual const Ogre::Vector3& getPosition(); - virtual const Ogre::Quaternion& getOrientation(); + virtual void setColor(float r, float g, float b, float a); + void setColor(const Ogre::ColourValue & c); + virtual void setPosition(const Ogre::Vector3 & position); + virtual void setOrientation(const Ogre::Quaternion & orientation); + virtual void setScale(const Ogre::Vector3 & scale); + virtual const Ogre::Vector3 & getPosition(); + virtual const Ogre::Quaternion & getOrientation(); /** * \brief Get the root scene node (pivot node) for this object * * @return The root scene node of this object */ - Ogre::SceneNode* getRootNode() { return scene_node_; } + Ogre::SceneNode * getRootNode() {return scene_node_; } /** * \brief Sets user data on all ogre objects we own */ - void setUserData( const Ogre::Any& data ); + void setUserData(const Ogre::Any & data); - Ogre::Entity* getEntity() { return entity_; } + Ogre::Entity * getEntity() {return entity_; } - Ogre::MaterialPtr getMaterial() { return material_; } + Ogre::MaterialPtr getMaterial() {return material_; } - static Ogre::Entity* createEntity(const std::string& name, Type shape_type, Ogre::SceneManager* scene_manager); + static Ogre::Entity * createEntity(const std::string & name, Type shape_type, + Ogre::SceneManager * scene_manager); protected: - Ogre::SceneNode* scene_node_; - Ogre::SceneNode* offset_node_; - Ogre::Entity* entity_; + Ogre::SceneNode * scene_node_; + Ogre::SceneNode * offset_node_; + Ogre::Entity * entity_; Ogre::MaterialPtr material_; std::string material_name_; @@ -120,4 +121,3 @@ class Shape : public Object } // namespace rviz #endif - diff --git a/rviz_rendering/src/rviz_rendering/camera_base.cpp b/rviz_rendering/src/rviz_rendering/camera_base.cpp index 04f918fd1..cb79cfc9a 100644 --- a/rviz_rendering/src/rviz_rendering/camera_base.cpp +++ b/rviz_rendering/src/rviz_rendering/camera_base.cpp @@ -41,22 +41,22 @@ namespace rviz { -CameraBase::CameraBase( Ogre::SceneManager* scene_manager ) -: scene_manager_( scene_manager ) -, relative_node_( NULL ) +CameraBase::CameraBase(Ogre::SceneManager * scene_manager) +: scene_manager_(scene_manager), + relative_node_(NULL) { std::stringstream ss; static uint32_t count = 0; ss << "CameraBase" << count++; - camera_ = scene_manager_->createCamera( ss.str() ); + camera_ = scene_manager_->createCamera(ss.str() ); } CameraBase::~CameraBase() { - scene_manager_->destroyCamera( camera_ ); + scene_manager_->destroyCamera(camera_); } -void CameraBase::setRelativeNode( Ogre::SceneNode* node ) +void CameraBase::setRelativeNode(Ogre::SceneNode * node) { relative_node_ = node; @@ -65,14 +65,14 @@ void CameraBase::setRelativeNode( Ogre::SceneNode* node ) update(); } -void CameraBase::setPosition( const Ogre::Vector3& position ) +void CameraBase::setPosition(const Ogre::Vector3 & position) { - setPosition( position.x, position.y, position.z ); + setPosition(position.x, position.y, position.z); } -void CameraBase::setOrientation( const Ogre::Quaternion& orientation ) +void CameraBase::setOrientation(const Ogre::Quaternion & orientation) { - setOrientation( orientation.x, orientation.y, orientation.z, orientation.w ); + setOrientation(orientation.x, orientation.y, orientation.z, orientation.w); } } // namespace rviz diff --git a/rviz_rendering/src/rviz_rendering/object.cpp b/rviz_rendering/src/rviz_rendering/object.cpp index 763edd357..d27bf846c 100644 --- a/rviz_rendering/src/rviz_rendering/object.cpp +++ b/rviz_rendering/src/rviz_rendering/object.cpp @@ -32,8 +32,8 @@ namespace rviz { -Object::Object( Ogre::SceneManager* scene_manager ) -: scene_manager_( scene_manager ) +Object::Object(Ogre::SceneManager * scene_manager) +: scene_manager_(scene_manager) { } diff --git a/rviz_rendering/src/rviz_rendering/orbit_camera.cpp b/rviz_rendering/src/rviz_rendering/orbit_camera.cpp index c716ea7d9..d12814857 100644 --- a/rviz_rendering/src/rviz_rendering/orbit_camera.cpp +++ b/rviz_rendering/src/rviz_rendering/orbit_camera.cpp @@ -50,17 +50,17 @@ static const float PITCH_LIMIT_HIGH = Ogre::Math::PI - 0.001; static const float YAW_START = Ogre::Math::PI;// - 0.001; static const float PITCH_START = Ogre::Math::HALF_PI; -OrbitCamera::OrbitCamera( Ogre::SceneManager* scene_manager ) -: CameraBase( scene_manager ) -, focal_point_( Ogre::Vector3::ZERO ) -, yaw_( YAW_START ) -, pitch_( PITCH_START ) -, distance_( 10.0f ) -{ - focal_point_object_ = new Shape( Shape::Sphere, scene_manager ); - focal_point_object_->setScale( Ogre::Vector3( 0.05f, 0.01f, 0.05f ) ); - focal_point_object_->setColor( 1.0f, 1.0f, 0.0f, 0.5f ); - focal_point_object_->getRootNode()->setVisible( false ); +OrbitCamera::OrbitCamera(Ogre::SceneManager * scene_manager) +: CameraBase(scene_manager), + focal_point_(Ogre::Vector3::ZERO), + yaw_(YAW_START), + pitch_(PITCH_START), + distance_(10.0f) +{ + focal_point_object_ = new Shape(Shape::Sphere, scene_manager); + focal_point_object_->setScale(Ogre::Vector3(0.05f, 0.01f, 0.05f) ); + focal_point_object_->setColor(1.0f, 1.0f, 0.0f, 0.5f); + focal_point_object_->getRootNode()->setVisible(false); update(); } @@ -72,22 +72,18 @@ OrbitCamera::~OrbitCamera() void OrbitCamera::normalizePitch() { - if ( pitch_ < PITCH_LIMIT_LOW ) - { + if (pitch_ < PITCH_LIMIT_LOW) { pitch_ = PITCH_LIMIT_LOW; - } - else if ( pitch_ > PITCH_LIMIT_HIGH ) - { + } else if (pitch_ > PITCH_LIMIT_HIGH) { pitch_ = PITCH_LIMIT_HIGH; } } void OrbitCamera::normalizeYaw() { - yaw_ = fmod( yaw_, Ogre::Math::TWO_PI ); + yaw_ = fmod(yaw_, Ogre::Math::TWO_PI); - if ( yaw_ < 0.0f ) - { + if (yaw_ < 0.0f) { yaw_ = Ogre::Math::TWO_PI + yaw_; } } @@ -96,9 +92,9 @@ Ogre::Vector3 OrbitCamera::getGlobalFocalPoint() { Ogre::Vector3 global_focal_point = focal_point_; - if ( relative_node_ ) - { - global_focal_point = relative_node_->getOrientation() * focal_point_ + relative_node_->getPosition(); + if (relative_node_) { + global_focal_point = relative_node_->getOrientation() * focal_point_ + + relative_node_->getPosition(); } return global_focal_point; @@ -108,27 +104,26 @@ void OrbitCamera::update() { Ogre::Vector3 global_focal_point = getGlobalFocalPoint(); - float x = distance_ * cos( yaw_ ) * sin( pitch_ ) + global_focal_point.x; - float y = distance_ * cos( pitch_ ) + global_focal_point.y; - float z = distance_ * sin( yaw_ ) * sin( pitch_ ) + global_focal_point.z; + float x = distance_ * cos(yaw_) * sin(pitch_) + global_focal_point.x; + float y = distance_ * cos(pitch_) + global_focal_point.y; + float z = distance_ * sin(yaw_) * sin(pitch_) + global_focal_point.z; - Ogre::Vector3 pos( x, y, z ); + Ogre::Vector3 pos(x, y, z); - if ( relative_node_ ) - { + if (relative_node_) { Ogre::Vector3 vec = pos - global_focal_point; pos = relative_node_->getOrientation() * vec + global_focal_point; camera_->setFixedYawAxis(true, relative_node_->getOrientation() * Ogre::Vector3::UNIT_Y); } - camera_->setPosition( pos ); - camera_->lookAt( global_focal_point ); + camera_->setPosition(pos); + camera_->lookAt(global_focal_point); - focal_point_object_->setPosition( global_focal_point ); + focal_point_object_->setPosition(global_focal_point); } -void OrbitCamera::yaw( float angle ) +void OrbitCamera::yaw(float angle) { yaw_ += angle; @@ -137,7 +132,7 @@ void OrbitCamera::yaw( float angle ) update(); } -void OrbitCamera::pitch( float angle ) +void OrbitCamera::pitch(float angle) { pitch_ += angle; @@ -146,7 +141,7 @@ void OrbitCamera::pitch( float angle ) update(); } -void OrbitCamera::roll( float angle ) +void OrbitCamera::roll(float angle) { } @@ -160,27 +155,26 @@ Ogre::Quaternion OrbitCamera::getOrientation() return camera_->getOrientation(); } -void OrbitCamera::calculatePitchYawFromPosition( const Ogre::Vector3& position ) +void OrbitCamera::calculatePitchYawFromPosition(const Ogre::Vector3 & position) { float x = position.x - focal_point_.x; float y = position.y - focal_point_.y; - pitch_ = acos( y / distance_ ); + pitch_ = acos(y / distance_); normalizePitch(); - float val = x / ( distance_ * sin( pitch_ ) ); + float val = x / ( distance_ * sin(pitch_) ); - yaw_ = acos( val ); + yaw_ = acos(val); Ogre::Vector3 direction = focal_point_ - position; - if ( direction.dotProduct( Ogre::Vector3::NEGATIVE_UNIT_Z ) < 0 ) - { + if (direction.dotProduct(Ogre::Vector3::NEGATIVE_UNIT_Z) < 0) { yaw_ = Ogre::Math::TWO_PI - yaw_; } } -void OrbitCamera::setFrom( CameraBase* camera ) +void OrbitCamera::setFrom(CameraBase * camera) { Ogre::Vector3 position = camera->getPosition(); Ogre::Quaternion orientation = camera->getOrientation(); @@ -188,74 +182,71 @@ void OrbitCamera::setFrom( CameraBase* camera ) Ogre::Vector3 direction = orientation * (Ogre::Vector3::NEGATIVE_UNIT_Z * distance_); focal_point_ = position + direction; - calculatePitchYawFromPosition( position ); + calculatePitchYawFromPosition(position); update(); } -void OrbitCamera::setOrientation( float x, float y, float z, float w ) +void OrbitCamera::setOrientation(float x, float y, float z, float w) { Ogre::Vector3 position = camera_->getPosition(); - Ogre::Quaternion orientation( w, x, y, z ); + Ogre::Quaternion orientation(w, x, y, z); Ogre::Vector3 direction = orientation * (Ogre::Vector3::NEGATIVE_UNIT_Z * distance_); focal_point_ = position + direction; - calculatePitchYawFromPosition( position ); + calculatePitchYawFromPosition(position); update(); } -void OrbitCamera::zoom( float amount ) +void OrbitCamera::zoom(float amount) { distance_ -= amount; - if ( distance_ <= MIN_DISTANCE ) - { + if (distance_ <= MIN_DISTANCE) { distance_ = MIN_DISTANCE; } update(); } -void OrbitCamera::setFocalPoint( const Ogre::Vector3& focal_point ) +void OrbitCamera::setFocalPoint(const Ogre::Vector3 & focal_point) { focal_point_ = focal_point; update(); } -void OrbitCamera::move( float x, float y, float z ) +void OrbitCamera::move(float x, float y, float z) { Ogre::Quaternion orientation = camera_->getOrientation(); - if ( relative_node_ ) - { + if (relative_node_) { orientation = relative_node_->getOrientation().Inverse() * orientation; } - focal_point_ += orientation * Ogre::Vector3( x, y, z ); + focal_point_ += orientation * Ogre::Vector3(x, y, z); update(); } -void OrbitCamera::setPosition( float x, float y, float z ) +void OrbitCamera::setPosition(float x, float y, float z) { - Ogre::Vector3 pos( x, y, z ); + Ogre::Vector3 pos(x, y, z); distance_ = (pos - getGlobalFocalPoint()).length(); - calculatePitchYawFromPosition( Ogre::Vector3( x, y, z ) ); + calculatePitchYawFromPosition(Ogre::Vector3(x, y, z) ); update(); } -void OrbitCamera::lookAt( const Ogre::Vector3& point ) +void OrbitCamera::lookAt(const Ogre::Vector3 & point) { Ogre::Vector3 focal_point = point; Ogre::Vector3 camera_position = camera_->getPosition(); - if ( relative_node_ ) - { + if (relative_node_) { Ogre::Vector3 rel_pos = relative_node_->getPosition(); Ogre::Quaternion rel_orient = relative_node_->getOrientation(); @@ -263,85 +254,80 @@ void OrbitCamera::lookAt( const Ogre::Vector3& point ) camera_position = rel_orient.Inverse() * ( camera_position - rel_pos ); } - distance_ = focal_point.distance( camera_position ); + distance_ = focal_point.distance(camera_position); focal_point_ = focal_point; update(); } -void OrbitCamera::mouseLeftDrag( int diff_x, int diff_y, bool ctrl, bool alt, bool shift ) +void OrbitCamera::mouseLeftDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift) { - yaw( diff_x*0.005 ); - pitch( -diff_y*0.005 ); + yaw(diff_x * 0.005); + pitch(-diff_y * 0.005); } -void OrbitCamera::mouseMiddleDrag( int diff_x, int diff_y, bool ctrl, bool alt, bool shift ) +void OrbitCamera::mouseMiddleDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift) { float fovY = camera_->getFOVy().valueRadians(); - float fovX = 2.0f * atan( tan( fovY / 2.0f ) * camera_->getAspectRatio() ); + float fovX = 2.0f * atan(tan(fovY / 2.0f) * camera_->getAspectRatio() ); int width = camera_->getViewport()->getActualWidth(); int height = camera_->getViewport()->getActualHeight(); - move( -((float)diff_x / (float)width) * distance_ * tan( fovX / 2.0f ) * 2.0f, ((float)diff_y / (float)height) * distance_ * tan( fovY / 2.0f ) * 2.0f, 0.0f ); + move(-((float)diff_x / (float)width) * distance_ * tan(fovX / 2.0f) * 2.0f, + ((float)diff_y / (float)height) * distance_ * tan(fovY / 2.0f) * 2.0f, 0.0f); } -void OrbitCamera::mouseRightDrag( int diff_x, int diff_y, bool ctrl, bool alt, bool shift ) +void OrbitCamera::mouseRightDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift) { - if (shift) - { + if (shift) { move(0.0f, 0.0f, diff_y * 0.1 * (distance_ / 10.0f)); - } - else - { - zoom( -diff_y * 0.1 * (distance_ / 10.0f) ); + } else { + zoom(-diff_y * 0.1 * (distance_ / 10.0f) ); } } -void OrbitCamera::scrollWheel( int diff, bool ctrl, bool alt, bool shift ) +void OrbitCamera::scrollWheel(int diff, bool ctrl, bool alt, bool shift) { - if (shift) - { + if (shift) { move(0.0f, 0.0f, -diff * 0.01 * (distance_ / 10.0f)); - } - else - { - zoom( diff * 0.01 * (distance_ / 10.0f) ); + } else { + zoom(diff * 0.01 * (distance_ / 10.0f) ); } } -void OrbitCamera::mouseLeftDown( int x, int y ) +void OrbitCamera::mouseLeftDown(int x, int y) { - focal_point_object_->getRootNode()->setVisible( true ); + focal_point_object_->getRootNode()->setVisible(true); } -void OrbitCamera::mouseMiddleDown( int x, int y ) +void OrbitCamera::mouseMiddleDown(int x, int y) { - focal_point_object_->getRootNode()->setVisible( true ); + focal_point_object_->getRootNode()->setVisible(true); } -void OrbitCamera::mouseRightDown( int x, int y ) +void OrbitCamera::mouseRightDown(int x, int y) { - focal_point_object_->getRootNode()->setVisible( true ); + focal_point_object_->getRootNode()->setVisible(true); } -void OrbitCamera::mouseLeftUp( int x, int y ) +void OrbitCamera::mouseLeftUp(int x, int y) { - focal_point_object_->getRootNode()->setVisible( false ); + focal_point_object_->getRootNode()->setVisible(false); } -void OrbitCamera::mouseMiddleUp( int x, int y ) +void OrbitCamera::mouseMiddleUp(int x, int y) { - focal_point_object_->getRootNode()->setVisible( false ); + focal_point_object_->getRootNode()->setVisible(false); } -void OrbitCamera::mouseRightUp( int x, int y ) +void OrbitCamera::mouseRightUp(int x, int y) { - focal_point_object_->getRootNode()->setVisible( false ); + focal_point_object_->getRootNode()->setVisible(false); } -void OrbitCamera::fromString(const std::string& str) +void OrbitCamera::fromString(const std::string & str) { std::istringstream iss(str); @@ -363,7 +349,8 @@ void OrbitCamera::fromString(const std::string& str) std::string OrbitCamera::toString() { std::ostringstream oss; - oss << pitch_ << " " << yaw_ << " " << distance_ << " " << focal_point_.x << " " << focal_point_.y << " " << focal_point_.z; + oss << pitch_ << " " << yaw_ << " " << distance_ << " " << focal_point_.x << " " << + focal_point_.y << " " << focal_point_.z; return oss.str(); } diff --git a/rviz_rendering/src/rviz_rendering/shape.cpp b/rviz_rendering/src/rviz_rendering/shape.cpp index 9ea68465b..1b1ad6021 100644 --- a/rviz_rendering/src/rviz_rendering/shape.cpp +++ b/rviz_rendering/src/rviz_rendering/shape.cpp @@ -43,40 +43,41 @@ namespace rviz { -Ogre::Entity* Shape::createEntity(const std::string& name, Type type, Ogre::SceneManager* scene_manager) +Ogre::Entity * Shape::createEntity(const std::string & name, Type type, + Ogre::SceneManager * scene_manager) { - if (type == Mesh) + if (type == Mesh) { return NULL; // the entity is initialized after the vertex data was specified + } std::string mesh_name; - switch (type) - { - case Cone: - mesh_name = "rviz_cone.mesh"; - break; - - case Cube: - mesh_name = "rviz_cube.mesh"; - break; - - case Cylinder: - mesh_name = "rviz_cylinder.mesh"; - break; - - case Sphere: - mesh_name = "rviz_sphere.mesh"; - break; - - default: - ROS_BREAK(); + switch (type) { + case Cone: + mesh_name = "rviz_cone.mesh"; + break; + + case Cube: + mesh_name = "rviz_cube.mesh"; + break; + + case Cylinder: + mesh_name = "rviz_cylinder.mesh"; + break; + + case Sphere: + mesh_name = "rviz_sphere.mesh"; + break; + + default: + ROS_BREAK(); } return scene_manager->createEntity(name, mesh_name); } -Shape::Shape( Type type, Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node ) -: Object( scene_manager ) -, type_(type) +Shape::Shape(Type type, Ogre::SceneManager * scene_manager, Ogre::SceneNode * parent_node) +: Object(scene_manager), + type_(type) { static uint32_t count = 0; std::stringstream ss; @@ -84,103 +85,104 @@ Shape::Shape( Type type, Ogre::SceneManager* scene_manager, Ogre::SceneNode* par entity_ = createEntity(ss.str(), type, scene_manager); - if ( !parent_node ) - { + if (!parent_node) { parent_node = scene_manager_->getRootSceneNode(); } scene_node_ = parent_node->createChildSceneNode(); offset_node_ = scene_node_->createChildSceneNode(); - if (entity_) - offset_node_->attachObject( entity_ ); + if (entity_) { + offset_node_->attachObject(entity_); + } ss << "Material"; material_name_ = ss.str(); - material_ = Ogre::MaterialManager::getSingleton().create( material_name_, ROS_PACKAGE_NAME ); + material_ = Ogre::MaterialManager::getSingleton().create(material_name_, ROS_PACKAGE_NAME); material_->setReceiveShadows(false); material_->getTechnique(0)->setLightingEnabled(true); - material_->getTechnique(0)->setAmbient( 0.5, 0.5, 0.5 ); + material_->getTechnique(0)->setAmbient(0.5, 0.5, 0.5); - if (entity_) + if (entity_) { entity_->setMaterialName(material_name_); + } #if (OGRE_VERSION_MAJOR <= 1 && OGRE_VERSION_MINOR <= 4) - if (entity_) + if (entity_) { entity_->setNormaliseNormals(true); + } #endif } Shape::~Shape() { - scene_manager_->destroySceneNode( scene_node_->getName() ); - scene_manager_->destroySceneNode( offset_node_->getName() ); + scene_manager_->destroySceneNode(scene_node_->getName() ); + scene_manager_->destroySceneNode(offset_node_->getName() ); - if (entity_) - scene_manager_->destroyEntity( entity_ ); + if (entity_) { + scene_manager_->destroyEntity(entity_); + } material_->unload(); Ogre::MaterialManager::getSingleton().remove(material_->getName()); } -void Shape::setColor(const Ogre::ColourValue& c) +void Shape::setColor(const Ogre::ColourValue & c) { - material_->getTechnique(0)->setAmbient( c * 0.5 ); - material_->getTechnique(0)->setDiffuse( c ); - - if ( c.a < 0.9998 ) - { - material_->getTechnique(0)->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA ); - material_->getTechnique(0)->setDepthWriteEnabled( false ); - } - else - { - material_->getTechnique(0)->setSceneBlending( Ogre::SBT_REPLACE ); - material_->getTechnique(0)->setDepthWriteEnabled( true ); + material_->getTechnique(0)->setAmbient(c * 0.5); + material_->getTechnique(0)->setDiffuse(c); + + if (c.a < 0.9998) { + material_->getTechnique(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA); + material_->getTechnique(0)->setDepthWriteEnabled(false); + } else { + material_->getTechnique(0)->setSceneBlending(Ogre::SBT_REPLACE); + material_->getTechnique(0)->setDepthWriteEnabled(true); } } -void Shape::setColor( float r, float g, float b, float a ) +void Shape::setColor(float r, float g, float b, float a) { setColor(Ogre::ColourValue(r, g, b, a)); } -void Shape::setOffset( const Ogre::Vector3& offset ) +void Shape::setOffset(const Ogre::Vector3 & offset) { - offset_node_->setPosition( offset ); + offset_node_->setPosition(offset); } -void Shape::setPosition( const Ogre::Vector3& position ) +void Shape::setPosition(const Ogre::Vector3 & position) { - scene_node_->setPosition( position ); + scene_node_->setPosition(position); } -void Shape::setOrientation( const Ogre::Quaternion& orientation ) +void Shape::setOrientation(const Ogre::Quaternion & orientation) { - scene_node_->setOrientation( orientation ); + scene_node_->setOrientation(orientation); } -void Shape::setScale( const Ogre::Vector3& scale ) +void Shape::setScale(const Ogre::Vector3 & scale) { - scene_node_->setScale( scale ); + scene_node_->setScale(scale); } -const Ogre::Vector3& Shape::getPosition() +const Ogre::Vector3 & Shape::getPosition() { return scene_node_->getPosition(); } -const Ogre::Quaternion& Shape::getOrientation() +const Ogre::Quaternion & Shape::getOrientation() { return scene_node_->getOrientation(); } -void Shape::setUserData( const Ogre::Any& data ) +void Shape::setUserData(const Ogre::Any & data) { - if (entity_) - entity_->getUserObjectBindings().setUserAny( data ); - else - ROS_ERROR("Shape not yet fully constructed. Cannot set user data. Did you add triangles to the mesh already?"); + if (entity_) { + entity_->getUserObjectBindings().setUserAny(data); + } else { + ROS_ERROR( + "Shape not yet fully constructed. Cannot set user data. Did you add triangles to the mesh already?"); + } } } // namespace rviz - From 0cc3378adc6e3d89584ee177650f6f6afc7b5c74 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Wed, 30 Aug 2017 18:05:59 -0700 Subject: [PATCH 3/4] cpplint pass over camera related cpp/h files --- .../include/rviz_rendering/camera_base.hpp | 288 ++++++++++-------- .../include/rviz_rendering/object.hpp | 77 +++-- .../include/rviz_rendering/orbit_camera.hpp | 201 ++++++++---- .../include/rviz_rendering/shape.hpp | 93 +++--- .../src/rviz_rendering/camera_base.cpp | 12 +- rviz_rendering/src/rviz_rendering/object.cpp | 6 +- .../src/rviz_rendering/orbit_camera.cpp | 35 ++- rviz_rendering/src/rviz_rendering/shape.cpp | 35 ++- 8 files changed, 460 insertions(+), 287 deletions(-) diff --git a/rviz_rendering/include/rviz_rendering/camera_base.hpp b/rviz_rendering/include/rviz_rendering/camera_base.hpp index 44088b66f..60214ae20 100644 --- a/rviz_rendering/include/rviz_rendering/camera_base.hpp +++ b/rviz_rendering/include/rviz_rendering/camera_base.hpp @@ -1,5 +1,6 @@ /* * Copyright (c) 2008, Willow Garage, Inc. + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without @@ -27,8 +28,10 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef OGRE_TOOLS_CAMERA_BASE_H_ -#define OGRE_TOOLS_CAMERA_BASE_H_ +#ifndef RVIZ_RENDERING__CAMERA_BASE_HPP_ +#define RVIZ_RENDERING__CAMERA_BASE_HPP_ + +#include #include #include @@ -40,56 +43,59 @@ class SceneNode; class SceneManager; } -namespace rviz +namespace rviz_rendering { +/// Generic interface for a camera. /** - * \class CameraBase - * \brief Generic interface for a camera - * - * Provides a interface that a camera can override, providing interchangeability between different camera types. + * Provides a interface that a camera can override, + * providing interchangeability between different camera types. * Specific implementation is left to the child class. */ class CameraBase { public: /** - * \brief Constructor - * @param scene_manager Scene manager this camera is displaying + * \param scene_manager Scene manager this camera is displaying */ - CameraBase(Ogre::SceneManager * scene_manager); + explicit CameraBase(Ogre::SceneManager * scene_manager); virtual ~CameraBase(); + /// Get the Ogre camera associated with this camera object. /** - * \brief Get the Ogre camera associated with this camera object - * @return The Ogre camera associated with this camera object + * \return The Ogre camera associated with this camera object */ - Ogre::Camera * getOgreCamera() {return camera_; } + Ogre::Camera * + getOgreCamera() {return camera_; } + /// Set a scene node that all camera transformations should be relative to. /** - * \brief Set a scene node that all camera transformations should be relative to - * @param node The node - */ - void setRelativeNode(Ogre::SceneNode * node); - /** - * \brief Called when the relative node changes + * \param node The node */ - virtual void relativeNodeChanged() {} + void + setRelativeNode(Ogre::SceneNode * node); - virtual void update() = 0; + /// Called when the relative node changes. + virtual + void + relativeNodeChanged() {} - /** - * \brief Set the position of the camera - */ - virtual void setPosition(const Ogre::Vector3 & position); - /** - * \brief Set the orientation of the camera - */ - virtual void setOrientation(const Ogre::Quaternion & orientation); + virtual + void + update() = 0; + + /// Set the position of the camera. + virtual + void + setPosition(const Ogre::Vector3 & position); + /// Set the orientation of the camera. + virtual + void + setOrientation(const Ogre::Quaternion & orientation); + + /// Yaw the camera. /** - * \brief Yaw the camera. - * * Calls to yaw are cumulative, so: * yaw(PI); * yaw(PI); @@ -97,131 +103,175 @@ class CameraBase * is equivalent to * yaw(2*PI); * - * @param angle Angle to yaw, in radians + * \param angle Angle to yaw, in radians */ - virtual void yaw(float angle) = 0; - /** - * \brief Pitch the camera. - * - * Calls to pitch are cumulative, so: - * pitch(PI); - * pitch(PI); - * - * is equivalent to - * pitch(2*PI); - * - * @param angle Angle to pitch, in radians - */ - virtual void pitch(float angle) = 0; - /** - * \brief Roll the camera. - * - * Calls to roll are cumulative, so: - * roll(PI); - * roll(PI); - * - * is equivalent to - * roll(2*PI); - * - * @param angle Angle to roll, in radians - */ - virtual void roll(float angle) = 0; + virtual + void + yaw(float angle) = 0; + /// Pitch the camera. /** - * \brief Set the orientation of the camera from a quaternion - */ - virtual void setOrientation(float x, float y, float z, float w) = 0; - /** - * \brief Set the position of the camera + * Calls to pitch are cumulative, so: + * pitch(PI); + * pitch(PI); + * + * is equivalent to + * pitch(2*PI); + * + * \param angle Angle to pitch, in radians */ - virtual void setPosition(float x, float y, float z) = 0; + virtual + void + pitch(float angle) = 0; + /// Roll the camera. /** - * \brief Set the position/orientation of this camera from another camera. + * Calls to roll are cumulative, so: + * roll(PI); + * roll(PI); * - * @param camera The camera to set from + * is equivalent to + * roll(2*PI); + * + * @param angle Angle to roll, in radians */ - virtual void setFrom(CameraBase * camera) = 0; + virtual + void + roll(float angle) = 0; + + /// Set the orientation of the camera from a quaternion. + virtual + void + setOrientation(float x, float y, float z, float w) = 0; + /// Set the position of the camera. + virtual + void + setPosition(float x, float y, float z) = 0; + + /// Set the position/orientation of this camera from another camera. /** - * \brief Get the position of this camera - * @return The position of this camera + * \param camera The camera to set from */ - virtual Ogre::Vector3 getPosition() = 0; + virtual + void + setFrom(CameraBase * camera) = 0; + + /// Get the position of this camera. /** - * \brief Get the orientation of this camera - * @return The orientation of this camera + * \return The position of this camera */ - virtual Ogre::Quaternion getOrientation() = 0; + virtual + Ogre::Vector3 + getPosition() = 0; + /// Get the orientation of this camera. /** - * \brief Point the camera at the specified point - * @param point The point to look at + * \return The orientation of this camera */ - virtual void lookAt(const Ogre::Vector3 & point) = 0; + virtual + Ogre::Quaternion + getOrientation() = 0; + /// Point the camera at the specified point. /** - * \brief Move the camera relative to its orientation - * - * @param x Distance to move along the X-axis - * @param y Distance to move along the Y-axis - * @param z Distance to move along the Z-axis + * \param point The point to look at */ - virtual void move(float x, float y, float z) = 0; - - virtual void mouseLeftDown(int x, int y) {} - virtual void mouseMiddleDown(int x, int y) {} - virtual void mouseRightDown(int x, int y) {} - virtual void mouseLeftUp(int x, int y) {} - virtual void mouseMiddleUp(int x, int y) {} - virtual void mouseRightUp(int x, int y) {} + virtual + void + lookAt(const Ogre::Vector3 & point) = 0; + /// Move the camera relative to its orientation. /** - * \brief Handle a left mouse button drag - * - * @param diff_x Pixels the mouse has moved in the (window space) x direction - * @param diff_y Pixels the mouse has moved in the (window space) y direction + * \param x Distance to move along the X-axis + * \param y Distance to move along the Y-axis + * \param z Distance to move along the Z-axis */ - virtual void mouseLeftDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift) = 0; + virtual + void + move(float x, float y, float z) = 0; // NOLINT: cpplint thinks this is std::move + + virtual + void + mouseLeftDown(int x, int y) {(void)x; (void)y;} + + virtual + void + mouseMiddleDown(int x, int y) {(void)x; (void)y;} + + virtual + void + mouseRightDown(int x, int y) {(void)x; (void)y;} + + virtual + void + mouseLeftUp(int x, int y) {(void)x; (void)y;} + + virtual + void + mouseMiddleUp(int x, int y) {(void)x; (void)y;} + + virtual + void + mouseRightUp(int x, int y) {(void)x; (void)y;} + + + /// Handle a left mouse button drag. /** - * \brief Handle a middle mouse button drag - * - * @param diff_x Pixels the mouse has moved in the (window space) x direction - * @param diff_y Pixels the mouse has moved in the (window space) y direction + * \param diff_x Pixels the mouse has moved in the (window space) x direction + * \param diff_y Pixels the mouse has moved in the (window space) y direction */ - virtual void mouseMiddleDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift) = 0; + virtual + void + mouseLeftDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift) = 0; + + /// Handle a middle mouse button drag. /** - * \brief Handle a right mouse button drag - * - * @param diff_x Pixels the mouse has moved in the (window space) x direction - * @param diff_y Pixels the mouse has moved in the (window space) y direction + * \param diff_x Pixels the mouse has moved in the (window space) x direction + * \param diff_y Pixels the mouse has moved in the (window space) y direction */ - virtual void mouseRightDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift) = 0; + virtual + void + mouseMiddleDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift) = 0; + + /// Handle a right mouse button drag. /** - * \brief Handle a scrollwheel change - * - * @param diff Number of "units" the scrollwheel has moved - * @todo Probably need to pass in how many units there are in a "click" of the wheel + * \param diff_x Pixels the mouse has moved in the (window space) x direction + * \param diff_y Pixels the mouse has moved in the (window space) y direction */ - virtual void scrollWheel(int diff, bool ctrl, bool alt, bool shift) = 0; + virtual + void + mouseRightDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift) = 0; + /// Handle a scrollwheel change. /** - * \brief Loads the camera's configure from the supplied string (generated through toString()) - * @param str The string to load from + * \param diff Number of "units" the scrollwheel has moved + * \todo Probably need to pass in how many units there are in a "click" of the wheel */ - virtual void fromString(const std::string & str) = 0; + virtual + void + scrollWheel(int diff, bool ctrl, bool alt, bool shift) = 0; + + /// Load the camera's configure from the supplied string (generated through toString()). /** - * \brief Returns a string representation of the camera's configuration + * \param str The string to load from */ - virtual std::string toString() = 0; + virtual + void + fromString(const std::string & str) = 0; + + /// Return a string representation of the camera's configuration. + virtual + std::string + toString() = 0; protected: - Ogre::Camera * camera_; ///< Ogre camera associated with this camera object - Ogre::SceneManager * scene_manager_; ///< Scene manager this camera is part of + Ogre::Camera * camera_; ///< Ogre camera associated with this camera object + Ogre::SceneManager * scene_manager_; ///< Scene manager this camera is part of Ogre::SceneNode * relative_node_; }; -} // namespace rviz +} // namespace rviz_rendering -#endif /*OGRE_TOOLS_CAMERA_BASE_H_*/ +#endif // RVIZ_RENDERING__CAMERA_BASE_HPP_ diff --git a/rviz_rendering/include/rviz_rendering/object.hpp b/rviz_rendering/include/rviz_rendering/object.hpp index 92eff3998..0ddf54095 100644 --- a/rviz_rendering/include/rviz_rendering/object.hpp +++ b/rviz_rendering/include/rviz_rendering/object.hpp @@ -1,5 +1,6 @@ /* * Copyright (c) 2008, Willow Garage, Inc. + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without @@ -27,8 +28,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef OGRE_TOOLS_OBJECT_H -#define OGRE_TOOLS_OBJECT_H +#ifndef RVIZ_RENDERING__OBJECT_HPP_ +#define RVIZ_RENDERING__OBJECT_HPP_ namespace Ogre { @@ -39,70 +40,80 @@ class Quaternion; class Any; } -namespace rviz +namespace rviz_rendering { -/** - * \class Object - * \brief Base class for visible objects, providing a minimal generic interface. - */ +/// Base class for visible objects, providing a minimal generic interface. class Object { public: /** - * - * @param scene_manager The scene manager this object should be part of. + * \param scene_manager The scene manager this object should be part of. */ - Object(Ogre::SceneManager * scene_manager); + explicit Object(Ogre::SceneManager * scene_manager); virtual ~Object() {} + /// Set the position of this object. /** - * \brief Set the position of this object - * @param Position vector position to set to. + * \param Position vector position to set to. */ - virtual void setPosition(const Ogre::Vector3 & position) = 0; + virtual + void + setPosition(const Ogre::Vector3 & position) = 0; + /// Set the orientation of the object. /** - * \brief Set the orientation of the object - * @param Orientation quaternion orientation to set to. + * \param Orientation quaternion orientation to set to. */ - virtual void setOrientation(const Ogre::Quaternion & orientation) = 0; + virtual + void + setOrientation(const Ogre::Quaternion & orientation) = 0; + /// Set the scale of the object. Always relative to the identity orientation of the object. /** - * \brief Set the scale of the object. Always relative to the identity orientation of the object. - * @param Scale vector scale to set to. + * \param Scale vector scale to set to. */ - virtual void setScale(const Ogre::Vector3 & scale) = 0; + virtual + void + setScale(const Ogre::Vector3 & scale) = 0; + /// Set the color of the object. Values are in the range [0, 1]. /** - * \brief Set the color of the object. Values are in the range [0, 1] - * @param r Red component - * @param g Green component - * @param b Blue component + * \param r Red component + * \param g Green component + * \param b Blue component */ - virtual void setColor(float r, float g, float b, float a) = 0; + virtual + void + setColor(float r, float g, float b, float a) = 0; + /// Get the local position of this object. /** - * \brief Get the local position of this object * @return The position */ - virtual const Ogre::Vector3 & getPosition() = 0; + virtual + const Ogre::Vector3 & + getPosition() = 0; + /// Get the local orientation of this object. /** - * \brief Get the local orientation of this object * @return The orientation */ - virtual const Ogre::Quaternion & getOrientation() = 0; + virtual + const Ogre::Quaternion & + getOrientation() = 0; + /// Set the user data on this object. /** - * \brief Set the user data on this object - * @param data + * \param data */ - virtual void setUserData(const Ogre::Any & data) = 0; + virtual + void + setUserData(const Ogre::Any & data) = 0; protected: Ogre::SceneManager * scene_manager_; ///< Ogre scene manager this object is part of }; -} // namespace rviz +} // namespace rviz_rendering -#endif /* OGRE_TOOLS_OBJECT_H */ +#endif // RVIZ_RENDERING__OBJECT_HPP_ diff --git a/rviz_rendering/include/rviz_rendering/orbit_camera.hpp b/rviz_rendering/include/rviz_rendering/orbit_camera.hpp index 4b9ba7401..70fbcba90 100644 --- a/rviz_rendering/include/rviz_rendering/orbit_camera.hpp +++ b/rviz_rendering/include/rviz_rendering/orbit_camera.hpp @@ -1,5 +1,6 @@ /* * Copyright (c) 2008, Willow Garage, Inc. + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without @@ -27,12 +28,15 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef OGRE_TOOLS_ORBIT_CAMERA_H_ -#define OGRE_TOOLS_ORBIT_CAMERA_H_ +#ifndef RVIZ_RENDERING__ORBIT_CAMERA_HPP_ +#define RVIZ_RENDERING__ORBIT_CAMERA_HPP_ + +#include -#include "camera_base.h" #include +#include "rviz_rendering/camera_base.hpp" + namespace Ogre { class Camera; @@ -40,14 +44,13 @@ class SceneNode; class SceneManager; } -namespace rviz +namespace rviz_rendering { class Shape; +/// An orbital camera, controlled by yaw, pitch, distance, and focal point. /** - * \brief An orbital camera, controlled by yaw, pitch, distance, and focal point - * * This camera is based on the equation of a sphere in spherical coordinates: @verbatim x = d*cos(theta)sin(phi) @@ -62,83 +65,159 @@ class Shape; class OrbitCamera : public CameraBase { public: - OrbitCamera(Ogre::SceneManager * scene_manager); + explicit OrbitCamera(Ogre::SceneManager * scene_manager); virtual ~OrbitCamera(); + /// Move in/out from the focal point, ie. adjust the distance by an amount. /** - * \brief Move in/out from the focal point, ie. adjust #distance_ by amount - * @param amount The distance to move. Positive amount moves towards the focal point, negative moves away + * Positive amount moves towards the focal point, negative moves away. + * + * \param amount The distance to move. */ - void zoom(float amount); + void + zoom(float amount); + + /// Set the focal point of the camera. /** - * \brief Set the focal point of the camera. Keeps the pitch/yaw/distance the same - * @param focal_point The new focal point + * Keeps the pitch/yaw/distance the same. + * + * \param focal_point The new focal point */ - void setFocalPoint(const Ogre::Vector3 & focal_point); + void + setFocalPoint(const Ogre::Vector3 & focal_point); - float getPitch() {return pitch_; } - float getYaw() {return yaw_; } - float getDistance() {return distance_; } - const Ogre::Vector3 & getFocalPoint() {return focal_point_; } + float + getPitch(); // {return pitch_; } - virtual void setFrom(CameraBase * camera); - virtual void yaw(float angle); - virtual void pitch(float angle); - virtual void roll(float angle); - virtual void setOrientation(float x, float y, float z, float w); - virtual void setPosition(float x, float y, float z); - virtual void move(float x, float y, float z); + float + getYaw(); // {return yaw_; } - virtual Ogre::Vector3 getPosition(); - virtual Ogre::Quaternion getOrientation(); + float + getDistance(); // {return distance_; } - virtual void lookAt(const Ogre::Vector3 & point); + const Ogre::Vector3 & + getFocalPoint(); // {return focal_point_; } - virtual void mouseLeftDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift); - virtual void mouseMiddleDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift); - virtual void mouseRightDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift); - virtual void scrollWheel(int diff, bool ctrl, bool alt, bool shift); + virtual + void + setFrom(CameraBase * camera); - /** - * \brief Calculates the camera's position and orientation from the yaw, pitch, distance and focal point - */ - virtual void update(); + virtual + void + yaw(float angle); + + virtual + void + pitch(float angle); + + virtual + void + roll(float angle); + + virtual + void + setOrientation(float x, float y, float z, float w); + + virtual + void + setPosition(float x, float y, float z); + + virtual + void + move(float x, float y, float z); // NOLINT: cpplint thinks this is std::move + + virtual + Ogre::Vector3 + getPosition(); + + virtual + Ogre::Quaternion + getOrientation(); + + virtual + void + lookAt(const Ogre::Vector3 & point); + + virtual + void + mouseLeftDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift); + + virtual + void + mouseMiddleDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift); - virtual void mouseLeftDown(int x, int y); - virtual void mouseMiddleDown(int x, int y); - virtual void mouseRightDown(int x, int y); - virtual void mouseLeftUp(int x, int y); - virtual void mouseMiddleUp(int x, int y); - virtual void mouseRightUp(int x, int y); + virtual + void + mouseRightDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift); - virtual void fromString(const std::string & str); - virtual std::string toString(); + virtual + void + scrollWheel(int diff, bool ctrl, bool alt, bool shift); + + /// Calculates the camera's position and orientation from yaw, pitch, distance, and focal point. + virtual + void + update(); + + virtual + void + mouseLeftDown(int x, int y); + + virtual + void + mouseMiddleDown(int x, int y); + + virtual + void + mouseRightDown(int x, int y); + + virtual + void + mouseLeftUp(int x, int y); + + virtual + void + mouseMiddleUp(int x, int y); + + virtual + void + mouseRightUp(int x, int y); + + virtual + void + fromString(const std::string & str); + + virtual + std::string + toString(); private: - Ogre::Vector3 getGlobalFocalPoint(); + Ogre::Vector3 + getGlobalFocalPoint(); + /// Calculate pitch and yaw values given a new position and the current focal point. /** - * \brief Calculates pitch and yaw values given a new position and the current focal point - * @param position Position to calculate the pitch/yaw for - */ - void calculatePitchYawFromPosition(const Ogre::Vector3 & position); - /** - * \brief Normalizes the camera's pitch, preventing it from reaching vertical (or turning upside down) + * \param position Position to calculate the pitch/yaw for */ - void normalizePitch(); - /** - * \brief Normalizes the camera's yaw in the range [0, 2*pi) - */ - void normalizeYaw(); + void + calculatePitchYawFromPosition(const Ogre::Vector3 & position); + + /// Normalize the camera's pitch, preventing it from reaching vertical (or turning upside down). + void + normalizePitch(); + + /// Normalize the camera's yaw in the range [0, 2*pi). + void + normalizeYaw(); - Ogre::Vector3 focal_point_; ///< The camera's focal point - float yaw_; ///< The camera's yaw (rotation around the y-axis), in radians - float pitch_; ///< The camera's pitch (rotation around the x-axis), in radians - float distance_; ///< The camera's distance from the focal point + Ogre::Vector3 focal_point_; ///< The camera's focal point + float yaw_; ///< The camera's yaw (rotation around the y-axis), in radians + float pitch_; ///< The camera's pitch (rotation around the x-axis), in radians + float distance_; ///< The camera's distance from the focal point Shape * focal_point_object_; }; -} // namespace rviz +} // namespace rviz_rendering -#endif /*OGRE_TOOLS_ORBIT_CAMERA_H_*/ +#endif // RVIZ_RENDERING__ORBIT_CAMERA_HPP_ diff --git a/rviz_rendering/include/rviz_rendering/shape.hpp b/rviz_rendering/include/rviz_rendering/shape.hpp index 5f62faa25..e9d87c5eb 100644 --- a/rviz_rendering/include/rviz_rendering/shape.hpp +++ b/rviz_rendering/include/rviz_rendering/shape.hpp @@ -27,15 +27,17 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef OGRE_TOOLS_SHAPE_H -#define OGRE_TOOLS_SHAPE_H +#ifndef RVIZ_RENDERING__SHAPE_HPP_ +#define RVIZ_RENDERING__SHAPE_HPP_ -#include "object.h" +#include #include #include #include +#include "rviz_rendering/object.hpp" + namespace Ogre { class SceneManager; @@ -44,11 +46,9 @@ class Any; class Entity; } -namespace rviz +namespace rviz_rendering { -/** - */ class Shape : public Object { public: @@ -62,50 +62,73 @@ class Shape : public Object }; /** - * \brief Constructor - * - * @param scene_manager The scene manager this object is associated with - * @param parent_node A scene node to use as the parent of this object. If NULL, uses the root scene node. + * \param scene_manager The scene manager this object is associated with + * \param parent_node A scene node to use as the parent of this object. + * If nullptr, uses the root scene node. */ Shape(Type shape_type, Ogre::SceneManager * scene_manager, Ogre::SceneNode * parent_node = NULL); virtual ~Shape(); - Type getType() {return type_; } + Type + getType(); // {return type_; } + /// Set the offset for this shape. /** - * \brief Set the offset for this shape - * * The default is no offset, which puts the pivot point directly in the center of the object. * - * @param offset Amount to offset the center of the object from the pivot point + * \param offset Amount to offset the center of the object from the pivot point */ - void setOffset(const Ogre::Vector3 & offset); + void + setOffset(const Ogre::Vector3 & offset); - virtual void setColor(float r, float g, float b, float a); - void setColor(const Ogre::ColourValue & c); - virtual void setPosition(const Ogre::Vector3 & position); - virtual void setOrientation(const Ogre::Quaternion & orientation); - virtual void setScale(const Ogre::Vector3 & scale); - virtual const Ogre::Vector3 & getPosition(); - virtual const Ogre::Quaternion & getOrientation(); + virtual + void + setColor(float r, float g, float b, float a); - /** - * \brief Get the root scene node (pivot node) for this object - * - * @return The root scene node of this object - */ - Ogre::SceneNode * getRootNode() {return scene_node_; } + void + setColor(const Ogre::ColourValue & c); + virtual + void + setPosition(const Ogre::Vector3 & position); + + virtual + void + setOrientation(const Ogre::Quaternion & orientation); + + virtual + void + setScale(const Ogre::Vector3 & scale); + + virtual + const Ogre::Vector3 & + getPosition(); + + virtual + const Ogre::Quaternion & + getOrientation(); + + /// Get the root scene node (pivot node) for this object. /** - * \brief Sets user data on all ogre objects we own + * \return The root scene node of this object */ - void setUserData(const Ogre::Any & data); + Ogre::SceneNode * + getRootNode(); // {return scene_node_; } + + /// Sets user data on all ogre objects we own. + void + setUserData(const Ogre::Any & data); - Ogre::Entity * getEntity() {return entity_; } + Ogre::Entity * + getEntity(); // {return entity_; } - Ogre::MaterialPtr getMaterial() {return material_; } + Ogre::MaterialPtr + getMaterial(); // {return material_; } - static Ogre::Entity * createEntity(const std::string & name, Type shape_type, + static Ogre::Entity * + createEntity( + const std::string & name, + Type shape_type, Ogre::SceneManager * scene_manager); protected: @@ -118,6 +141,6 @@ class Shape : public Object Type type_; }; -} // namespace rviz +} // namespace rviz_rendering -#endif +#endif // RVIZ_RENDERING__SHAPE_HPP_ diff --git a/rviz_rendering/src/rviz_rendering/camera_base.cpp b/rviz_rendering/src/rviz_rendering/camera_base.cpp index cb79cfc9a..034febdbc 100644 --- a/rviz_rendering/src/rviz_rendering/camera_base.cpp +++ b/rviz_rendering/src/rviz_rendering/camera_base.cpp @@ -27,7 +27,10 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "camera_base.h" +#include "rviz_rendering/camera_base.hpp" + +#include +#include #include #include @@ -35,10 +38,7 @@ #include #include -#include -#include - -namespace rviz +namespace rviz_rendering { CameraBase::CameraBase(Ogre::SceneManager * scene_manager) @@ -75,4 +75,4 @@ void CameraBase::setOrientation(const Ogre::Quaternion & orientation) setOrientation(orientation.x, orientation.y, orientation.z, orientation.w); } -} // namespace rviz +} // namespace rviz_rendering diff --git a/rviz_rendering/src/rviz_rendering/object.cpp b/rviz_rendering/src/rviz_rendering/object.cpp index d27bf846c..03fd23281 100644 --- a/rviz_rendering/src/rviz_rendering/object.cpp +++ b/rviz_rendering/src/rviz_rendering/object.cpp @@ -27,9 +27,9 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "object.h" +#include "rviz_rendering/object.hpp" -namespace rviz +namespace rviz_rendering { Object::Object(Ogre::SceneManager * scene_manager) @@ -37,4 +37,4 @@ Object::Object(Ogre::SceneManager * scene_manager) { } -} // namespace rviz +} // namespace rviz_rendering diff --git a/rviz_rendering/src/rviz_rendering/orbit_camera.cpp b/rviz_rendering/src/rviz_rendering/orbit_camera.cpp index d12814857..5382aedb0 100644 --- a/rviz_rendering/src/rviz_rendering/orbit_camera.cpp +++ b/rviz_rendering/src/rviz_rendering/orbit_camera.cpp @@ -27,27 +27,29 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "orbit_camera.h" -#include "shape.h" +#include "rviz_rendering/orbit_camera.hpp" + +#include +#include +#include #include +#include #include #include #include -#include #include -#include -#include +#include "rviz_rendering/shape.hpp" #define MIN_DISTANCE 0.01 -namespace rviz +namespace rviz_rendering { static const float PITCH_LIMIT_LOW = 0.001; static const float PITCH_LIMIT_HIGH = Ogre::Math::PI - 0.001; -static const float YAW_START = Ogre::Math::PI;// - 0.001; +static const float YAW_START = Ogre::Math::PI; static const float PITCH_START = Ogre::Math::HALF_PI; OrbitCamera::OrbitCamera(Ogre::SceneManager * scene_manager) @@ -58,7 +60,7 @@ OrbitCamera::OrbitCamera(Ogre::SceneManager * scene_manager) distance_(10.0f) { focal_point_object_ = new Shape(Shape::Sphere, scene_manager); - focal_point_object_->setScale(Ogre::Vector3(0.05f, 0.01f, 0.05f) ); + focal_point_object_->setScale(Ogre::Vector3(0.05f, 0.01f, 0.05f)); focal_point_object_->setColor(1.0f, 1.0f, 0.0f, 0.5f); focal_point_object_->getRootNode()->setVisible(false); @@ -218,7 +220,7 @@ void OrbitCamera::setFocalPoint(const Ogre::Vector3 & focal_point) update(); } -void OrbitCamera::move(float x, float y, float z) +void OrbitCamera::move(float x, float y, float z) // NOLINT: cpplint thinks this is std::move { Ogre::Quaternion orientation = camera_->getOrientation(); @@ -274,15 +276,17 @@ void OrbitCamera::mouseMiddleDrag(int diff_x, int diff_y, bool ctrl, bool alt, b int width = camera_->getViewport()->getActualWidth(); int height = camera_->getViewport()->getActualHeight(); - move(-((float)diff_x / (float)width) * distance_ * tan(fovX / 2.0f) * 2.0f, - ((float)diff_y / (float)height) * distance_ * tan(fovY / 2.0f) * 2.0f, 0.0f); - + move( // NOLINT: cpplint thinks this is std::move + -(static_cast(diff_x) / static_cast(width)) * distance_ * tan(fovX / 2.0f) * 2.0f, + (static_cast(diff_y) / static_cast(height)) * distance_ * tan(fovY / 2.0f) * 2.0f, + 0.0f); } void OrbitCamera::mouseRightDrag(int diff_x, int diff_y, bool ctrl, bool alt, bool shift) { if (shift) { - move(0.0f, 0.0f, diff_y * 0.1 * (distance_ / 10.0f)); + move( // NOLINT: cpplint thinks this is std::move + 0.0f, 0.0f, diff_y * 0.1 * (distance_ / 10.0f)); } else { zoom(-diff_y * 0.1 * (distance_ / 10.0f) ); } @@ -291,7 +295,8 @@ void OrbitCamera::mouseRightDrag(int diff_x, int diff_y, bool ctrl, bool alt, bo void OrbitCamera::scrollWheel(int diff, bool ctrl, bool alt, bool shift) { if (shift) { - move(0.0f, 0.0f, -diff * 0.01 * (distance_ / 10.0f)); + move( // NOLINT: cpplint thinks this is std::move + 0.0f, 0.0f, -diff * 0.01 * (distance_ / 10.0f)); } else { zoom(diff * 0.01 * (distance_ / 10.0f) ); } @@ -355,4 +360,4 @@ std::string OrbitCamera::toString() return oss.str(); } -} // namespace rviz +} // namespace rviz_rendering diff --git a/rviz_rendering/src/rviz_rendering/shape.cpp b/rviz_rendering/src/rviz_rendering/shape.cpp index 1b1ad6021..c986fd81c 100644 --- a/rviz_rendering/src/rviz_rendering/shape.cpp +++ b/rviz_rendering/src/rviz_rendering/shape.cpp @@ -27,28 +27,32 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "shape.h" -#include +#include "rviz_rendering/shape.hpp" + +#include +#include +#include -#include -#include -#include -#include #include #include -#include +#include +#include +#include #include -#include +#include +#include -namespace rviz +namespace rviz_rendering { -Ogre::Entity * Shape::createEntity(const std::string & name, Type type, +Ogre::Entity * +Shape::createEntity( + const std::string & name, + Type type, Ogre::SceneManager * scene_manager) { if (type == Mesh) { - return NULL; // the entity is initialized after the vertex data was specified - + return NULL; // the entity is initialized after the vertex data was specified } std::string mesh_name; switch (type) { @@ -69,7 +73,7 @@ Ogre::Entity * Shape::createEntity(const std::string & name, Type type, break; default: - ROS_BREAK(); + throw std::runtime_error("unexpected shape type"); } return scene_manager->createEntity(name, mesh_name); @@ -181,8 +185,9 @@ void Shape::setUserData(const Ogre::Any & data) entity_->getUserObjectBindings().setUserAny(data); } else { ROS_ERROR( - "Shape not yet fully constructed. Cannot set user data. Did you add triangles to the mesh already?"); + "Shape not yet fully constructed. " + "Cannot set user data. Did you add triangles to the mesh already?"); } } -} // namespace rviz +} // namespace rviz_rendering From 72415ebc5fa8422e705eb8b0770996d67d8d2ba5 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Wed, 30 Aug 2017 19:13:19 -0700 Subject: [PATCH 4/4] wip (revert this and redo commits) --- rviz_rendering/CMakeLists.txt | 7 +- .../include/rviz_rendering/shape.hpp | 1 + .../src/rviz_rendering/camera_base.cpp | 3 +- rviz_rendering/src/rviz_rendering/object.cpp | 1 + .../src/rviz_rendering/orbit_camera.cpp | 3 + .../src/rviz_rendering/render_window.cpp | 67 ++++++++++--------- rviz_rendering/src/rviz_rendering/shape.cpp | 20 +++--- 7 files changed, 57 insertions(+), 45 deletions(-) diff --git a/rviz_rendering/CMakeLists.txt b/rviz_rendering/CMakeLists.txt index 9aede40d1..4c7f20b8b 100644 --- a/rviz_rendering/CMakeLists.txt +++ b/rviz_rendering/CMakeLists.txt @@ -8,7 +8,8 @@ if(NOT CMAKE_CXX_STANDARD) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic -Werror) + # add_compile_options(-Wall -Wextra -Wpedantic -Werror) + add_compile_options(-Wall -Wextra -Wpedantic) endif() find_package(ament_cmake REQUIRED) @@ -52,12 +53,16 @@ set(headers_with_q_object add_library(${PROJECT_NAME} ${headers_with_q_object} + src/rviz_rendering/camera_base.cpp src/rviz_rendering/logging.cpp + src/rviz_rendering/object.cpp src/rviz_rendering/ogre_logging.cpp + src/rviz_rendering/orbit_camera.cpp src/rviz_rendering/render_system.cpp src/rviz_rendering/render_window.cpp src/rviz_rendering/render_window_impl.cpp src/rviz_rendering/resource_config.cpp + src/rviz_rendering/shape.cpp ) target_link_libraries(${PROJECT_NAME} rviz_ogre_vendor::OgreMain diff --git a/rviz_rendering/include/rviz_rendering/shape.hpp b/rviz_rendering/include/rviz_rendering/shape.hpp index e9d87c5eb..f887e1a78 100644 --- a/rviz_rendering/include/rviz_rendering/shape.hpp +++ b/rviz_rendering/include/rviz_rendering/shape.hpp @@ -1,5 +1,6 @@ /* * Copyright (c) 2008, Willow Garage, Inc. + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without diff --git a/rviz_rendering/src/rviz_rendering/camera_base.cpp b/rviz_rendering/src/rviz_rendering/camera_base.cpp index 034febdbc..aa575c3d8 100644 --- a/rviz_rendering/src/rviz_rendering/camera_base.cpp +++ b/rviz_rendering/src/rviz_rendering/camera_base.cpp @@ -1,5 +1,6 @@ /* * Copyright (c) 2008, Willow Garage, Inc. + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without @@ -43,7 +44,7 @@ namespace rviz_rendering CameraBase::CameraBase(Ogre::SceneManager * scene_manager) : scene_manager_(scene_manager), - relative_node_(NULL) + relative_node_(nullptr) { std::stringstream ss; static uint32_t count = 0; diff --git a/rviz_rendering/src/rviz_rendering/object.cpp b/rviz_rendering/src/rviz_rendering/object.cpp index 03fd23281..e2d29c050 100644 --- a/rviz_rendering/src/rviz_rendering/object.cpp +++ b/rviz_rendering/src/rviz_rendering/object.cpp @@ -1,5 +1,6 @@ /* * Copyright (c) 2008, Willow Garage, Inc. + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without diff --git a/rviz_rendering/src/rviz_rendering/orbit_camera.cpp b/rviz_rendering/src/rviz_rendering/orbit_camera.cpp index 5382aedb0..2d5d4d7b0 100644 --- a/rviz_rendering/src/rviz_rendering/orbit_camera.cpp +++ b/rviz_rendering/src/rviz_rendering/orbit_camera.cpp @@ -1,5 +1,6 @@ /* * Copyright (c) 2008, Willow Garage, Inc. + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without @@ -116,6 +117,7 @@ void OrbitCamera::update() Ogre::Vector3 vec = pos - global_focal_point; pos = relative_node_->getOrientation() * vec + global_focal_point; + // relative_node_->attachObject(camera_); camera_->setFixedYawAxis(true, relative_node_->getOrientation() * Ogre::Vector3::UNIT_Y); } @@ -145,6 +147,7 @@ void OrbitCamera::pitch(float angle) void OrbitCamera::roll(float angle) { + (void)angle; } Ogre::Vector3 OrbitCamera::getPosition() diff --git a/rviz_rendering/src/rviz_rendering/render_window.cpp b/rviz_rendering/src/rviz_rendering/render_window.cpp index 74521ea58..23ed4fa32 100644 --- a/rviz_rendering/src/rviz_rendering/render_window.cpp +++ b/rviz_rendering/src/rviz_rendering/render_window.cpp @@ -117,16 +117,22 @@ ToString(const EnumType & enumValue) bool RenderWindow::event(QEvent * event) { - // // printf("in RenderWindow::event(QEvent *)\n"); - // switch (event->type()) { - // case QEvent::UpdateRequest: - // // m_update_pending = false; - // this->renderNow(); - // return true; - // default: - // return QWindow::event(event); - // } - return QWindow::event(event); + qDebug() << + "[" << QTime::currentTime().toString("HH:mm:ss:zzz") << "]:" << + "event->type() ==" << ToString(event->type()); + switch (event->type()) { + case QEvent::Resize: + if (this->isExposed()) { + impl_->resize(this->width(), this->height()); + } + return QWindow::event(event); + case QEvent::UpdateRequest: + this->renderNow(); + return true; + default: + return QWindow::event(event); + } + // return QWindow::event(event); } void @@ -143,28 +149,25 @@ RenderWindow::exposeEvent(QExposeEvent * expose_event) bool RenderWindow::eventFilter(QObject * target, QEvent * event) { - // printf("in RenderWindow::eventFilter(QObject *, QEvent *)\n"); - if (target == this) { - qDebug() << - "[" << QTime::currentTime().toString() << "]: " << - "event->type() == " << ToString(event->type()) << ", " << - "target == " << target; - switch (event->type()) { - case QEvent::Resize: - if (this->isExposed()) { - impl_->resize(this->width(), this->height()); - } else { - printf("here\n"); - } - return false; - case QEvent::UpdateRequest: - this->renderNow(); - return true; - default: - return QWindow::event(event); - } - } - return false; + // if (target == this) { + // qDebug() << + // "[" << QTime::currentTime().toString("HH:mm:ss:zzz") << "]:" << + // "event->type() ==" << ToString(event->type()) << + // "target ==" << target; + // switch (event->type()) { + // case QEvent::Resize: + // if (this->isExposed()) { + // impl_->resize(this->width(), this->height()); + // } + // return false; + // case QEvent::UpdateRequest: + // this->renderNow(); + // return true; + // default: + // return QWindow::event(event); + // } + // } + return QWindow::eventFilter(target, event); } } // namespace rviz_rendering diff --git a/rviz_rendering/src/rviz_rendering/shape.cpp b/rviz_rendering/src/rviz_rendering/shape.cpp index c986fd81c..3131be69e 100644 --- a/rviz_rendering/src/rviz_rendering/shape.cpp +++ b/rviz_rendering/src/rviz_rendering/shape.cpp @@ -1,5 +1,6 @@ /* * Copyright (c) 2008, Willow Garage, Inc. + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without @@ -42,6 +43,8 @@ #include #include +#include "rviz_rendering/logging.hpp" + namespace rviz_rendering { @@ -101,7 +104,8 @@ Shape::Shape(Type type, Ogre::SceneManager * scene_manager, Ogre::SceneNode * pa ss << "Material"; material_name_ = ss.str(); - material_ = Ogre::MaterialManager::getSingleton().create(material_name_, ROS_PACKAGE_NAME); + // TODO(wjwwood): remove hard coded rviz_rendering package name, was ROS_PACKAGE_NAME + material_ = Ogre::MaterialManager::getSingleton().create(material_name_, "rviz_rendering"); material_->setReceiveShadows(false); material_->getTechnique(0)->setLightingEnabled(true); material_->getTechnique(0)->setAmbient(0.5, 0.5, 0.5); @@ -109,25 +113,19 @@ Shape::Shape(Type type, Ogre::SceneManager * scene_manager, Ogre::SceneNode * pa if (entity_) { entity_->setMaterialName(material_name_); } - -#if (OGRE_VERSION_MAJOR <= 1 && OGRE_VERSION_MINOR <= 4) - if (entity_) { - entity_->setNormaliseNormals(true); - } -#endif } Shape::~Shape() { - scene_manager_->destroySceneNode(scene_node_->getName() ); - scene_manager_->destroySceneNode(offset_node_->getName() ); + scene_manager_->destroySceneNode(scene_node_->getName()); + scene_manager_->destroySceneNode(offset_node_->getName()); if (entity_) { scene_manager_->destroyEntity(entity_); } material_->unload(); - Ogre::MaterialManager::getSingleton().remove(material_->getName()); + Ogre::MaterialManager::getSingleton().remove(material_->getName(), "rviz_rendering"); } void Shape::setColor(const Ogre::ColourValue & c) @@ -184,7 +182,7 @@ void Shape::setUserData(const Ogre::Any & data) if (entity_) { entity_->getUserObjectBindings().setUserAny(data); } else { - ROS_ERROR( + RVIZ_RENDERING_LOG_ERROR( "Shape not yet fully constructed. " "Cannot set user data. Did you add triangles to the mesh already?"); }