From a2be1712f18fdb933ea6ac39b758b91e424a1947 Mon Sep 17 00:00:00 2001 From: Martin Idel Date: Tue, 1 Oct 2019 23:59:03 +0200 Subject: [PATCH] Migrate Axes Display (#429) * Move axes display * Make display compile and fix linters * Hide axis when transform in error * Minor refactoring of axes - Shapes are now unique pointers - When accessing them, return a reference only (no need for anything else * Add visual test * Update README * Fix indentation in plugins_description * Use getFrameStd instead of getStdString To ensure we get a frame ID in the case the property is set to the fixed frame. Signed-off-by: Jacob Perron --- README.md | 29 ++-- rviz/src/rviz/default_plugin/axes_display.cpp | 126 ----------------- rviz_default_plugins/CMakeLists.txt | 16 +++ .../displays/axes/axes_display.hpp | 62 +++++---- rviz_default_plugins/plugins_description.xml | 11 ++ .../displays/axes/axes_display.cpp | 129 ++++++++++++++++++ .../pose/pose_display_selection_handler.cpp | 6 +- .../axes_display_visual_test_ref.png | Bin 0 -> 20320 bytes .../axes/axes_display_visual_test.cpp | 52 +++++++ .../page_objects/axes_display_page_object.cpp | 53 +++++++ .../page_objects/axes_display_page_object.hpp | 45 ++++++ .../include/rviz_rendering/objects/axes.hpp | 40 +++--- .../src/rviz_rendering/objects/axes.cpp | 14 +- 13 files changed, 384 insertions(+), 199 deletions(-) delete mode 100644 rviz/src/rviz/default_plugin/axes_display.cpp rename rviz/src/rviz/default_plugin/axes_display.h => rviz_default_plugins/include/rviz_default_plugins/displays/axes/axes_display.hpp (66%) create mode 100644 rviz_default_plugins/src/rviz_default_plugins/displays/axes/axes_display.cpp create mode 100644 rviz_default_plugins/test/reference_images/axes_display_visual_test_ref.png create mode 100644 rviz_default_plugins/test/rviz_default_plugins/displays/axes/axes_display_visual_test.cpp create mode 100644 rviz_default_plugins/test/rviz_default_plugins/page_objects/axes_display_page_object.cpp create mode 100644 rviz_default_plugins/test/rviz_default_plugins/page_objects/axes_display_page_object.hpp diff --git a/README.md b/README.md index 9ca98b3fe..4b7e70979 100644 --- a/README.md +++ b/README.md @@ -14,14 +14,16 @@ For some displays, the [documentation is updated](docs/FEATURES.md). | Displays | Tools | View Controller | Panels | | --------------------- | ------------- | --------------------- | --------------- | -| Camera | Move Camera | Orbit | Displays | -| Fluid Pressure | Focus Camera | XY Orbit | Help | -| Grid | Measure | First Person | Selections | -| Grid Cells | Select | Third Person Follower | Tool Properties | -| Illuminance | 2D Goal Pose | Top Down Orthographic | Views | -| Image | Publish Point | -| Laser Scan | Initial Pose | -| Map | Interact | +| Axes | Move Camera | Orbit | Displays | +| Camera | Focus Camera | XY Orbit | Help | +| Fluid Pressure | Measure | First Person | Selections | +| Grid | Select | Third Person Follower | Tool Properties | +| Grid Cells | 2D Nav Goal | Top Down Orthographic | Views | +| Illuminance | Publish Point | +| Image | Initial Pose | +| Interactive Marker | Interact | +| Laser Scan | +| Map | | Marker | | Marker Array | | Odometry | @@ -41,19 +43,16 @@ For some displays, the [documentation is updated](docs/FEATURES.md). ### Not yet ported These features have not been ported to `ros2/rviz` yet. -| Displays | Tools | Panels | -| -------------------- | ------------ | ------ | -| Axes | | Time | -| DepthCloud | +| Displays | Panels | +| -------------------- | ------ | +| DepthCloud | Time | | Effort | -| Interactive Marker | -| Oculus | | Pose With Covariance | Other features: - Filtering of Topic lists by topic type -- Message filters - Image transport features +- Stereo In case you wished to see those features in RViz for ROS 2, feel free to add a pull request. Make sure to read the developer guide below and the migration guide. diff --git a/rviz/src/rviz/default_plugin/axes_display.cpp b/rviz/src/rviz/default_plugin/axes_display.cpp deleted file mode 100644 index 9e93cb1ec..000000000 --- a/rviz/src/rviz/default_plugin/axes_display.cpp +++ /dev/null @@ -1,126 +0,0 @@ -/* - * Copyright (c) 2008, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * * Neither the name of the Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived from - * this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - -#include - -#include -#include - -#include "rviz/display_context.h" -#include "rviz/frame_manager.h" -#include "rviz/ogre_helpers/axes.h" -#include "rviz/properties/float_property.h" -#include "rviz/properties/tf_frame_property.h" - -#include "axes_display.h" - -namespace rviz -{ - -AxesDisplay::AxesDisplay() - : Display() - , axes_( 0 ) -{ - frame_property_ = new TfFrameProperty( "Reference Frame", TfFrameProperty::FIXED_FRAME_STRING, - "The TF frame these axes will use for their origin.", - this, NULL, true ); - - length_property_ = new FloatProperty( "Length", 1.0, - "Length of each axis, in meters.", - this, SLOT( updateShape() )); - length_property_->setMin( 0.0001 ); - - radius_property_ = new FloatProperty( "Radius", 0.1, - "Radius of each axis, in meters.", - this, SLOT( updateShape() )); - radius_property_->setMin( 0.0001 ); -} - -AxesDisplay::~AxesDisplay() -{ - delete axes_; -} - -void AxesDisplay::onInitialize() -{ - frame_property_->setFrameManager( context_->getFrameManager() ); - - axes_ = new Axes( scene_manager_, 0, length_property_->getFloat(), radius_property_->getFloat() ); - axes_->getSceneNode()->setVisible( isEnabled() ); -} - -void AxesDisplay::onEnable() -{ - axes_->getSceneNode()->setVisible( true ); -} - -void AxesDisplay::onDisable() -{ - axes_->getSceneNode()->setVisible( false ); -} - -void AxesDisplay::updateShape() -{ - axes_->set( length_property_->getFloat(), radius_property_->getFloat() ); - context_->queueRender(); -} - -void AxesDisplay::update( float dt, float ros_dt ) -{ - QString qframe = frame_property_->getFrame(); - std::string frame = qframe.toStdString(); - - Ogre::Vector3 position; - Ogre::Quaternion orientation; - if( context_->getFrameManager()->getTransform( frame, ros::Time(), position, orientation )) - { - axes_->setPosition( position ); - axes_->setOrientation( orientation ); - setStatus( StatusProperty::Ok, "Transform", "Transform OK" ); - } - else - { - std::string error; - if( context_->getFrameManager()->transformHasProblems( frame, ros::Time(), error )) - { - setStatus( StatusProperty::Error, "Transform", QString::fromStdString( error )); - } - else - { - setStatus( StatusProperty::Error, - "Transform", - "Could not transform from [" + qframe + "] to Fixed Frame [" + fixed_frame_ + "] for an unknown reason" ); - } - } -} - -} // namespace rviz - -#include -PLUGINLIB_EXPORT_CLASS( rviz::AxesDisplay, rviz::Display ) diff --git a/rviz_default_plugins/CMakeLists.txt b/rviz_default_plugins/CMakeLists.txt index c0233aadb..e7d7fcbfd 100644 --- a/rviz_default_plugins/CMakeLists.txt +++ b/rviz_default_plugins/CMakeLists.txt @@ -76,6 +76,7 @@ find_package(visualization_msgs REQUIRED) # These need to be added in the add_library() call so AUTOMOC detects them. set(rviz_default_plugins_headers_to_moc + include/rviz_default_plugins/displays/axes/axes_display.hpp include/rviz_default_plugins/displays/camera/camera_display.hpp include/rviz_default_plugins/displays/fluid_pressure/fluid_pressure_display.hpp include/rviz_default_plugins/displays/grid/grid_display.hpp @@ -136,6 +137,7 @@ set(rviz_default_plugins_headers_to_moc ) set(rviz_default_plugins_source_files + src/rviz_default_plugins/displays/axes/axes_display.cpp src/rviz_default_plugins/displays/camera/camera_display.cpp src/rviz_default_plugins/displays/grid/grid_display.cpp src/rviz_default_plugins/displays/grid_cells/grid_cells_display.cpp @@ -632,6 +634,20 @@ if(BUILD_TESTING) target_link_libraries(transformer_guard_test ${TEST_LINK_LIBRARIES}) endif() + ament_add_gtest(axes_display_visual_test + test/rviz_default_plugins/displays/axes/axes_display_visual_test.cpp + test/rviz_default_plugins/page_objects/axes_display_page_object.cpp + ${SKIP_VISUAL_TESTS} + TIMEOUT 180) + if(TARGET axes_display_visual_test) + target_include_directories(axes_display_visual_test PUBLIC + ${TEST_INCLUDE_DIRS} + ${rviz_visual_testing_framework_INCLUDE_DIRS}) + target_link_libraries(axes_display_visual_test + ${TEST_LINK_LIBRARIES} + rviz_visual_testing_framework::rviz_visual_testing_framework) + endif() + ament_add_gtest(camera_display_visual_test test/rviz_default_plugins/displays/camera/camera_display_visual_test.cpp test/rviz_default_plugins/publishers/camera_info_publisher.hpp diff --git a/rviz/src/rviz/default_plugin/axes_display.h b/rviz_default_plugins/include/rviz_default_plugins/displays/axes/axes_display.hpp similarity index 66% rename from rviz/src/rviz/default_plugin/axes_display.h rename to rviz_default_plugins/include/rviz_default_plugins/displays/axes/axes_display.hpp index f6e9708bc..4309d820b 100644 --- a/rviz/src/rviz/default_plugin/axes_display.h +++ b/rviz_default_plugins/include/rviz_default_plugins/displays/axes/axes_display.hpp @@ -27,55 +27,63 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef RVIZ_AXES_DISPLAY_H -#define RVIZ_AXES_DISPLAY_H +#ifndef RVIZ_DEFAULT_PLUGINS__DISPLAYS__AXES__AXES_DISPLAY_HPP_ +#define RVIZ_DEFAULT_PLUGINS__DISPLAYS__AXES__AXES_DISPLAY_HPP_ -#include "rviz/display.h" +#include -namespace rviz -{ +#include "rviz_common/display.hpp" +namespace rviz_rendering +{ class Axes; +} + +namespace rviz_common +{ +namespace properties +{ class FloatProperty; class TfFrameProperty; +} +} -/** @brief Displays a set of XYZ axes at the origin of a chosen frame. */ -class AxesDisplay: public Display +namespace rviz_default_plugins { -Q_OBJECT +namespace displays +{ + +class AxesDisplay : public rviz_common::Display +{ + Q_OBJECT + public: AxesDisplay(); - virtual ~AxesDisplay(); - void onInitialize(); + ~AxesDisplay() override; - /** - * \brief Set the parameters for the axes - * @param length Length of each axis - * @param radius Radius of each axis - */ - void set( float length, float radius ); + void onInitialize() override; // Overrides from Display - virtual void update(float dt, float ros_dt); + void update(float dt, float ros_dt) override; protected: - // overrides from Display - virtual void onEnable(); - virtual void onDisable(); + void onEnable() override; + + void onDisable() override; private Q_SLOTS: - /** @brief Update the length and radius of the axes object from property values. */ void updateShape(); private: - Axes* axes_; ///< Handles actually drawing the axes + std::shared_ptr axes_; - FloatProperty* length_property_; - FloatProperty* radius_property_; - TfFrameProperty* frame_property_; + rviz_common::properties::FloatProperty * length_property_; + rviz_common::properties::FloatProperty * radius_property_; + rviz_common::properties::TfFrameProperty * frame_property_; }; -} // namespace rviz +} // namespace displays +} // namespace rviz_default_plugins - #endif +#endif // RVIZ_DEFAULT_PLUGINS__DISPLAYS__AXES__AXES_DISPLAY_HPP_ diff --git a/rviz_default_plugins/plugins_description.xml b/rviz_default_plugins/plugins_description.xml index c0679e649..f4903e7ae 100644 --- a/rviz_default_plugins/plugins_description.xml +++ b/rviz_default_plugins/plugins_description.xml @@ -2,6 +2,17 @@ + + + Displays an axis at the Target Frame's origin. + <a href="http://www.ros.org/wiki/rviz/DisplayTypes/Axes">More Information</a>. + + + +#include + +#include +#include + +#include "rviz_rendering/objects/axes.hpp" +#include "rviz_common/display_context.hpp" +#include "rviz_common/frame_manager_iface.hpp" +#include "rviz_common/properties/float_property.hpp" +#include "rviz_common/properties/tf_frame_property.hpp" + + +namespace rviz_default_plugins +{ +namespace displays +{ + +AxesDisplay::AxesDisplay() +: Display(), axes_(nullptr) +{ + frame_property_ = new rviz_common::properties::TfFrameProperty( + "Reference Frame", + rviz_common::properties::TfFrameProperty::FIXED_FRAME_STRING, + "The TF frame these axes will use for their origin.", + this, nullptr, true); + + length_property_ = new rviz_common::properties::FloatProperty( + "Length", 1.0f, "Length of each axis, in meters.", this, SLOT(updateShape())); + length_property_->setMin(0.0001f); + + radius_property_ = new rviz_common::properties::FloatProperty( + "Radius", 0.1f, "Radius of each axis, in meters.", this, SLOT(updateShape())); + radius_property_->setMin(0.0001f); +} + +AxesDisplay::~AxesDisplay() = default; + +void AxesDisplay::onInitialize() +{ + frame_property_->setFrameManager(context_->getFrameManager()); + + axes_ = std::make_shared( + scene_manager_, scene_node_, length_property_->getFloat(), radius_property_->getFloat()); + axes_->getSceneNode()->setVisible(isEnabled()); +} + +void AxesDisplay::onEnable() +{ + axes_->getSceneNode()->setVisible(true); +} + +void AxesDisplay::onDisable() +{ + axes_->getSceneNode()->setVisible(false); +} + +void AxesDisplay::updateShape() +{ + axes_->set(length_property_->getFloat(), radius_property_->getFloat()); + context_->queueRender(); +} + +void AxesDisplay::update(float dt, float ros_dt) +{ + (void) dt; + (void) ros_dt; + + std::string frame = frame_property_->getFrameStd(); + + Ogre::Vector3 position; + Ogre::Quaternion orientation; + if (context_->getFrameManager()->getTransform( + frame, context_->getClock()->now(), position, orientation)) + { + axes_->getSceneNode()->setVisible(true); + axes_->setPosition(position); + axes_->setOrientation(orientation); + setStatus(rviz_common::properties::StatusProperty::Ok, "Transform", "Transform OK"); + } else { + std::string error; + if (context_->getFrameManager()->transformHasProblems( + frame, context_->getClock()->now(), error)) + { + setStatus( + rviz_common::properties::StatusProperty::Error, "Transform", QString::fromStdString(error)); + } else { + setMissingTransformToFixedFrame(frame); + } + axes_->getSceneNode()->setVisible(false); + } +} + +} // namespace displays +} // namespace rviz_default_plugins + +#include // NOLINT +PLUGINLIB_EXPORT_CLASS(rviz_default_plugins::displays::AxesDisplay, rviz_common::Display) diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/pose/pose_display_selection_handler.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/pose/pose_display_selection_handler.cpp index 96415c792..0ad262b0f 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/pose/pose_display_selection_handler.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/pose/pose_display_selection_handler.cpp @@ -97,11 +97,11 @@ rviz_common::interaction::V_AABB PoseDisplaySelectionHandler::getAABBs( display_->arrow_->getShaft()->getEntity()->getWorldBoundingBox(derive_world_bounding_box)); } else { aabbs.push_back( - display_->axes_->getXShape()->getEntity()->getWorldBoundingBox(derive_world_bounding_box)); + display_->axes_->getXShape().getEntity()->getWorldBoundingBox(derive_world_bounding_box)); aabbs.push_back( - display_->axes_->getYShape()->getEntity()->getWorldBoundingBox(derive_world_bounding_box)); + display_->axes_->getYShape().getEntity()->getWorldBoundingBox(derive_world_bounding_box)); aabbs.push_back( - display_->axes_->getZShape()->getEntity()->getWorldBoundingBox(derive_world_bounding_box)); + display_->axes_->getZShape().getEntity()->getWorldBoundingBox(derive_world_bounding_box)); } } return aabbs; diff --git a/rviz_default_plugins/test/reference_images/axes_display_visual_test_ref.png b/rviz_default_plugins/test/reference_images/axes_display_visual_test_ref.png new file mode 100644 index 0000000000000000000000000000000000000000..a9bc964ec97cba608197d12d05813fe2b13d7649 GIT binary patch literal 20320 zcmeHPdsvj!x}Sk@9F&E|Gm$=~<)s>e%6$oaJoE8(6nEApI zwMwOv^)f3}C!^bD-9Gr__b*1iKCt|)&p#WddLZ|y72Uo3Y1xqEzZpz91IDRN`uVK> zJ@&WUkwUS#{u{l-<3mrKBHwEDlu5H){(P@gT`85v*I{0To8ym%S!%MzxctN(y8F19 z1Jvee>1vTyqjUT@yRAl_lcM%2G}P!NM#rBpy|%^m7kcKAAu$$MjODd1qDZrq!`#@q z5zeAuU6Rnnw>{WY{P%VqNdsE|Oqf2q<-u%_e2!wwg{!lV0KT z5Hff8x~J`{*<}JS>OTR-mjRRd2$+ZPa(@KOBgQ;3rAI#Ik@I~NmHvN)YfG4D&}!AF zlRnZ8TcT3BN>XVQciR$+gbAXoU|DH)|DloP(U&}b8kQFl;n_Q+-DoWu#*+!*imfc| z2+pTuBSGQz*Cdtx=9rU<1;hW^rvEiXeS<#;5ow32%?+uPP-S&^`XBF=bM0&E&rSMs zL)k>DkSwvhO;~LZJd>m{|8u`J@hQqkBLC(o^DUFdFJfW$`RJ_v!FwG8OBb_LsHBA? z7K{>!PxcDE@|iq7kG;J+mkIY9aw3T|JL;P)@>SQ2HydfM!s2LMRaB@+hb-@KZcWkZ zTH}c|+R*RWJimL&NT4FTctWW%E@0wpWa4BEVHsRth{COIq)40AFQsZzs41UkXxL&Z zaz;bC#CSq?Ht(eMr#0H29v~h3f=w873lmOPmZlrB+aJ%Vn_0Af*P6ky{Hez^g4ce% z*{jZ7Yv^r$^J;$3QM@;ahm`lRkqV8VbxU&AN4oO`+96FE!Ka(tS6(1-y{}>JJA7_R zeHUWP7J1_BvhKH|+Mhf%b%6G(3FcmB@X`goqb9u6hJV(2lm$)%PQgz?9m#})gk`(_ zY=W@S$+W2>*i?5e^Xn^oq(T!i;C?B&fyW8`)Nu+ocNv4CV}io1b%0RUPuo7${jjfD zRbBkb;h+!bt#-V1*CX31ZqjcUDiw}_I{Kxk&QO=o2HAI>?vR4tO^X4S=rw@ovbL0orlxBh>~ePofV zOxBbp{XjtVfa^|aR%V5YBHcs1v1|D`eLyw$U2Fi*#qs6`3Ux(r>4I*OR! z`<^`h5at`tWbK2erF`rlLjoUr(drr5kEx^>yQd!;jpaGY$K1@C@#gI>t3^c`W*C0j z4eZ&?Y$Xz0JnNIG77;&iROu5iiOCyUqmpD>%S_g#IMCE^9_Dz#YTZN4(>CwjTGN@( zq%ZbsXQP_j0^kL(%a-3Np&pFNom|Y<`aSkpF2}uO9FRzkjZ69NZxohdQ&7i`0Z{+8 z721;f60Y0h!@T&;EU`MivtPY{2~ttf(+@NZkv9r2aYP;jz*J$JM>b8wS*WH_f8S3k zw2jKy<;g~6Oi9z!B!{_s=4+Yz6C93rPrKlw(@j(s110DoTFf~BvSF48C=R3cOW`zesuI=wHBO~o~vu9GQYxP1Z?{KzLn{NE?eY<4>0U+1BiR z)ei>>TNUmiWe|&IUo3O8K?H> zmnC=`1IPJFvxR*)V{vfNJbIgM>CGYwQ%NOTk1L$KO*1v$-q>wv{69Z!qK_zQ^jSS*!wvqYx!CD z4OloWIlXr>U-FAu_%E|Z-={_&DymFv&M3GI)nolbz&x}xU6@e`5sdv!ed~zJ4g+28dhWAN==9>!q=Be5>v?ShP(pEG zgZWhkPSA0H)4;*`y$cgy|D*E_T+)*)#$@rQ9-R;oPaBNS@~0=*Q+OYOV6p{k5MO2g z=C=F{%OiA17RYf#*^`1q&gQ`J%)*{#E@GY}n3H7DoM7f~ym@x8i!Yp5!5O`M2SO|< zyO=E;$EQ|n>N$k7c5|L66qKO&KgFi@9`F&LI(W_?hD9Ge%V=z#cj|7=qcOun*}^5~ zSvoP8?{VrrS^IN@fplXdyln54tk~gh_SHr5`c?!-?%AXaHUp{F# z_k@Xg$dL@Kv_qtR7GU2yRXgu0D?%jz_|H?c9QYamUcltPcyT^-O&cG1$= z*}!-EyVgMySrIG|Vz%$IE=6F4*lo~I9FmhhoMppn5vJbXXT6K;3s2(^y5mDlgKqQM z+}1WkhK6$MY5p`5FkVkpk1wDSonRkkiU>7jFkOqE0a=@kL2-z{eFTm=G8!}e!x;1?+e#GtPLA5V-5Vx{ z@?Vh0U5@c~{uI1}Uk}^?qsG|8Y`Bb)cyph{L?K-_sB^kSKgO3bPoWzZH-?F8fL|kV z6RS8i2j=l<4QyH^n22dRcA#>JY3~YvCr~)dOL$crg?f&{9!&6-JbnmcgyspRGVkCB zZffqML|W*)i&s7KxYD|!d44odrX9Io>s`y#ZQ&|weTu2f!YA#^C#B3FRqL%%u}L?K zBa#gfv1fJuBJEeO_)H|6hgxbnm$vA=xReoG$`OUo)do~C2QaAdryF#LGI_mK96MAU zFhNMPd3Fh(Y%EO{5I&8@=x-I`$pvJ1n6K_hk#^);6z_l8a2oEcyHS6LA6ND;IxY78 z87?c%c;9-VQ6JCk!w62thmI@x59k|M&_oB>$3JB7CIeRQ*@Udel;OZ)e5lF7a!kV} zrj?qQDWK5t;hXRzsf2kcV-X`z)!`|?Cn{u0^@pidLEKowA;E1mes20#T^KBTxz_tX z4AML}XKZxvRd|Si5!JC!#Q4kX3FSLsO=q{?g<0q2{Xn`kkq6f3kRuUgfY-kU{DmvQ z!Vn0+)KEfPYhi)KPNW)M94=pF@%YO`--Bri$FsdXV(yMYs!L*K*uF^l0uisCN-oNM{>QIx z%bWUWCW+iWt1_Nxvkk`)c!W}rW;xm3E<9w_`BW=w?%defs(&E8>Y1*)G)b|^CLhGu zji3>~K4$7Nb>OzukTyKTqYL(slTvk8P7x1>gZCim>6V1qabrC^n$7!?$tA!`cG1a% zj@uO1uBXP0eAnuwFetw=&7YD~#0`L6K=DBPT<-x_2aN~ai`RZvQ~7mva=pGMAR(w+ z?LmHYHJ`iIHeQe)EtnXG1l%b8R}ld8GL^ll&xUHkSJ_kprM}E4J80fTNS#-Ih5U(f ziY?q#Au&KyK_q;FQWFX{l$y}aN;RY$=_gCWV7R*vrMYmnni0%0Jq;GG^nQ^XbdPo{ zi0a(2gck&1?aOLYC3Db_g>t0Z>fGY5;aV(tM_ouO#?fWuTZZYUhJt5cJ43|yHRfqijCEa*NF0+X{)MW!l*``1#tfP2VHlupoh~VD8s|<^|syX zJeemdjo$-K=Y*`FP|?F%8RgHn)f3Gr*ktGRWzKMC*Y~?Ren`?DyCzVUx#}r^o6uf^GO=csIWoKboIcDhEas)#%W^m^^0(!D zWS}fj=nEUfd8m(LQW)ktKrTA8EmaT1Yv!n`{|={&LzEp@sqh?6;da>dM>dt!41ZcC z$NySC(PvEU)+^bul>#cxj$f(WhrR*ry32nzKfWb)=NR+nRM|=VRuwa9%^% zn>%6B4YjG=7NA(pm4#C=d?gS~sj$NfFAR^QFlA4l2?hxzzfdeWj)N^zonb8lByb%8 z(p)NEr8{g#WSO-fbu6Pc0ClsgEvY|1#7T6N3$c3Aj5yfGpHoYK3F zffb11EA`^Q$$+ZU_Z9`pUfG=a}39lry#FST49Sx zH4<lw3DQ7yjLxw}Pw z#2&BN3v@^Wv%vA?4vr__%yZFV34ewFd8~~9nR?SMW(5Nzw3+}(`!hfgL7?pT=Uw(& zLV!fTcq2Z%KvL{-kwQ%;c*Xq@?~^QHc9v7wYo(qtl;kbLkm@-cp&Mnjnvdg_C+qHo zn?A>hyRQdXulE(ZloY5fV?x#3J48XHTDGACMW9&2B~h z-q}(r$GPMo#-M6I0KMRl2aKunludqe@05m>&~IV7-@$c?;IS?|E2mLqvtgI#Qq=)= zTR{2WI$li~S728m4s3g_+h;w+Fxn=9$JG23`K*o(NDm2ef(w#tA3}SN{EAU`+n_M4 zRwrrdl-HV<-Ee^wN%&B8hTekQDnI30yFpuFdj>;)>(dyw%D<2drQWdt6h{EcOE@)I zEY(q=MD5)U!h!pB#6d6n@rbQg#K;TpPM2tgsS`iZ^eWf7ROi-Yn` zhYKhH1d19i&IJ^y5HB4oD@&bA8y}My`<$q7j}zW{2Fs#idV1{7U^&R8X?2li7L(>> z;bcg271F>L3}4riKEma8A{&q@u8h|s1UQ^OP@c}DS+s@L3ru@hn&%m1%()?$cMgb_ znNl^%DK1NeD58;?K626AZ!n-ms{B*rnarsD4z4xd_|^p*oLhm-ivPl9ETfFJVKGMj zmgP&jFgT`eV;(QK_;Yx}AvmTYJ{;obL)%t6!B_k)!aa>czZu}hOSM&!AFX0(uvV`H z;6n-=k3n!$39%JG? z2c*@g*iph$?`%}EECPqk=n4)U>NS98vp zvN|2-G1YV(M8%I_&fvODK%ky8XW8|hJ;H-~po-3CggbGB5k{UAMIP(|H!C-ky&WQpQJUd1K4j#$?m-Os zXdnWqp|3K$dU$4)hr@8F#tQ08i@BFOZ%gUa$AcR$T7gG@4S=aM|a2(SmoM(o7If_fpiGL9s&-?N*L3`;E z=xZ0l#C0NBtGG$m_?r2LEwM9B_smEMJkkmzrtz=2XoPM8qBZsD2(t;ns@RJb;~sti z&fW@S-U!KD+=q>*!&Z%Tf_xm6{95D3ATpZg_mXcX;tV|v}$e};mr7X@?%lFU~=zLeNu^^PZ2ITk!mllp` zJ5dthc>Lof!s81ULoD6Q^-}E&QYlV<#YauF|_C%&4E!HAt}oTGUTa)992)gSWg!emlW; zktQ@r?Qm-3w^>Sgc4^T=aM1Pbf>8Bz8Nm_m3I{6S4330zYZyH~ciB1a(1@lVyZrbf z{b(6=6wX!M=Mus3j+0gJ)&SJ7p1(k4Z)Z3t?3&6Dc0swO)z12leAf=*3n@d9u_i@2 zHU@8fm57j{{=nI*3J{~g4jzu5xy0Dv?_dWif}kj@rFh@shpeRrzJI)?cz$_-7guW3P)Cbn6LnjB^nK?GzB>{Tvj-HD7u95jkc$#Gtj97JSx4zqiD0ODm{zmr31#;t^#KPNwMoomg3lnI?i|!QKsGV9 zpK}%im=&dSDCl;+Sw(_fMsoxQ0)e9cKP>FrXRiOkMKIpLA~m(|`v}LX*e{IERtkTS z#CcNfQa3O$x=!}KfSCDu+2m?NO4V6AsJ4a&aZ_b{H{Ag>_ndU&5ZO~YeXQg_mbpkl zhgRm-+YkH?`Sm>}yIR??W+#s?&pH1{gzrF?J5JkkCXxWHJp$kgYu>Dkf==WYpRT_^ z(M8=;kHJCvefj;^+f+%=*=owH1|=NB%3UD%gU~NKtJ|zw?DY%=q5Xb#g&k7Lg(_HI z{@vMgkyvfm_6sT^j!|?IgAxI5h=%VkM9iP@lO5PI!)zBBc%K;z z{q)JZS=mdfB+i+HN}WFB4+kip$l@EnKnRM;~ZNz)9v4&B=6 zYy}CZp3=pBv&)Z4>WwiPz7?>-lYhxIqDAA=&hCv@3v0sk6JuNKbvk5ebVJw+#mPb* z7WMP(RZE;jw%Rl!f~` zaZ_8WC1PmPlpG~qQw18&oOa-!u+m~YbIHGt@TPUIEKu1kyw!iJ^`27|dbm>HvtNGo zYjx)J70`FyohEm&SeK*KIp>nHyTJ3Z`qCkN#+xl|J9fF7-*JjH2~g8Jp*g{OpnUOj zDA-5j@9D6U=^oAn$5TDeP^H*{NC} z(akD?_sp5_GS&SZ^=@hzxU4=q?_0>45NmOjRmo)CJjn;Pa%-&`*B(hGdkKmzY#=Kx zY%uHO0@qn7)TJo~j!uWHqC=@JvQpnpLwQ;8&!|!uv@@v*V^2>krab(zI&t7P@Cuf^ zBXs9=$Q}hc;ekuyHKV>nebO*li1Hmd%j%RVwtz{ZMiT!OL;b2rk! zAvbKwihP?5TsL|ZL_Lk$GbdQli9&l!n7IT|LG$DV+GCG1E={HT9cjIYuHEh~UPS{( z*{_PPFvva8<%?@K`C3wBPpr4lUC(~Q>T2>p@2#ESjH=*EMx9PHh~kP+@rnxr=mru4 zGj=GDkhFIWb*4^M5(BQaW#G=-+|&BkW!1{`ob0If`khvp!wZ+v4cvZ;m;3bonzr8V z?v?T85LEx;4R$!9DAF3D?#LGnis%Sfo6-DAmCU{?@wp_{LxXf7NHIv6PPeT=4)1#w zFkfiwjtd7P>JE!2$#TFv=~2S+3wVib5ZzPJCw%Y`c4V z6RxQpx8!kP49Y-Qc8~lpTtDQsNBPL5Y~J~E>7wUZuSo>vZW~1fAqkZ5G0X`J9}LHQe~ z@$xrCPoNg0LvIJ3l?dy|hYjaptC}&{v;imqqWC_gNNW$v<9jnjXdny}QSu`ctCp5R zC`=l~Dn1^c@JW+0*+Du;42nayL0efkr_NN8atLA)SlcCp)JSlSB(vQ~;KM+cb-aV? z0H+JJ4lCT~x*B~ReFmd14umNYA*rHi^Vqc1nu=+U3<7m9?GZQX22a(t@DS~f6CaE@ za1w3AJ%-y!8JG47mv+`sY!`=8RV5A!0O2?X0U{tan8vN;<>*y9%mi-l=KXOJX3*;S zyfX|p`s60mOx&C?T-<@PISK=4rrT=MMCQB1_!al<<=O`vT;)Bes3=9fiOWR2tLQP? zL2Ob-;*bPa;ca2Ag08vIK;ktJZ8a!-#YCgV1P+v(Wlw8ZFxU4D#C0>Fn@iou&BpR# z29gkC07J(F216oTCrU`RD^}{a0uv&JV@oJI9PxynK>I$+NH1Bxa~Qtw>5SyvQ7z|a zRlz|HLjz(Y_!ZB|&)YgWkt85@I<1{6QO!VlDux+(%H6JAx|B6$>Sr6}(hrzq$dOYe zg1^l!%+1xhJ9l8>_H1XW|J8E(ETEaC)pX+Qw{KBWQW07)C57b0YsM*X1sJK7L|#!V zo_xV*z{kuC$b=A4mV0OooOn@zfohke;k2`Wq0D4G%ufE1)T@f#;aSwljpNF|Lulcn zZczp|OK{QOx?>dd4!9Fz5P_+uyNtvZ9>>PfW_p`$z^O1W@Fl1bt+ykX=P5$|=#GA7 z1MZ}0;RDp1g2rXuoRW2xFFYoZPaQKAH@Wof0l(g*d=67@rN~WF5B@iPz|@W=-t2u& zO}teISJ+b(Z{o#44-0o?m-B^d^t@xbVI?V3fd21JEYH2Jt}ybmmHb>R{lXX38>*YN{7xUYcH9e5vo<}2P^&*>gcg*&vVZ-J+! z4-&B8_KlJ3z@u)LBKXla7=Od0s0q@fCwjwPXrJHIU?vPaM+1Qu22R_c!`?y4Ui}ey z3H`rgAj(#(^SC!WHwJpQ3lL~95Fd}Q&n+;pPi7I{#$2C4TvShZ!W7V{}d) zhWDYCz1wV`9o*o3f&j<6Q3am`GYp)3lp9(U>_0>)XdGSCI8Lz;V5D)1g$($Z8&eBw zYRr;%960cGfU?Y*fJy+-3jCe6ArpHes^LqPMlRXlx`|A(lK)hq5(vpo&c`9}n(amjBq3+HYUSR|rTXz`vkdySM?4-WjPlEbNz5`NuBM@h>a1^ZuZ(WZ)_8Mx5d{)X&(-kZBT7D={$+g#eUF$-d<9 z<#mL}aHR5V!VR$+0qRrO!Ds~NNc@Q1^*1c!g5Xn?NaRCM$Xx{JJdU_jgX#q4ZNYbd zrJQy2mDFzj)H4U>N~@xvL0=+ZY%XFcwTHvG&8Gt=VZ9G(v-wnfdPhMQc<&CO-a7hB z3(g$h7b2aCr|-jX=L?73^0^LV!d5eIZl_Ee8`^~pW%GrH)2DV&Rs(Km=oSSFA4Xd~ zask?KbeYYzaS7tj)jSU+KTn_t)ue7+&EdF&P}u6JQ>#=m=|}JuQsG=pWXBhe`MZ6u z`1GUK5C}%FuRX&f2X4`7*vCjzgEoobA#t%oUj*Kwk0ge`7vQ@(vrilYu7yXt0&;|#^5Os2w%@o@-`m+1+Ehxno360 zl4P$!A33b?0^ST>51;IuSR;OBBZ<|IvaK7n93%e$C43h^d%-701j%=D5-Eb-^SsGb%DOjh +#include + +#include "rviz_visual_testing_framework/visual_test_fixture.hpp" +#include "rviz_visual_testing_framework/visual_test_publisher.hpp" + +#include "../../page_objects/axes_display_page_object.hpp" + +TEST_F(VisualTestFixture, axes_display_visual_test) { + // we need tf data to display axes - this can be achieved via a dummy publisher + auto path_publisher = std::make_unique( + std::make_shared("test_node"), "other_frame"); + + setCamPose(Ogre::Vector3(10, 0, 0)); + setCamLookAt(Ogre::Vector3(0, 0, 0)); + + auto axes_display = addDisplay(); + axes_display->setReferenceFrame("map"); + axes_display->setAxesLength(5); + axes_display->setAxesRadius(3); + + assertMainWindowIdentity(); +} diff --git a/rviz_default_plugins/test/rviz_default_plugins/page_objects/axes_display_page_object.cpp b/rviz_default_plugins/test/rviz_default_plugins/page_objects/axes_display_page_object.cpp new file mode 100644 index 000000000..648954828 --- /dev/null +++ b/rviz_default_plugins/test/rviz_default_plugins/page_objects/axes_display_page_object.cpp @@ -0,0 +1,53 @@ +/* + * Copyright (c) 2019, Martin Idel + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "axes_display_page_object.hpp" + +#include +#include + +#include "rviz_visual_testing_framework/test_helpers.hpp" + +AxesDisplayPageObject::AxesDisplayPageObject() +: BasePageObject(0, "Axes") +{} + +void AxesDisplayPageObject::setReferenceFrame(const QString & reference_frame) +{ + setComboBox("Reference Frame", reference_frame); +} + +void AxesDisplayPageObject::setAxesLength(float length) +{ + setFloat("Length", length); +} + +void AxesDisplayPageObject::setAxesRadius(float radius) +{ + setFloat("Radius", radius); +} diff --git a/rviz_default_plugins/test/rviz_default_plugins/page_objects/axes_display_page_object.hpp b/rviz_default_plugins/test/rviz_default_plugins/page_objects/axes_display_page_object.hpp new file mode 100644 index 000000000..6657ba278 --- /dev/null +++ b/rviz_default_plugins/test/rviz_default_plugins/page_objects/axes_display_page_object.hpp @@ -0,0 +1,45 @@ +/* + * Copyright (c) 2019, Martin Idel + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef RVIZ_DEFAULT_PLUGINS__PAGE_OBJECTS__AXES_DISPLAY_PAGE_OBJECT_HPP_ +#define RVIZ_DEFAULT_PLUGINS__PAGE_OBJECTS__AXES_DISPLAY_PAGE_OBJECT_HPP_ + +#include "rviz_visual_testing_framework/page_objects/base_page_object.hpp" + +class AxesDisplayPageObject : public BasePageObject +{ +public: + AxesDisplayPageObject(); + + void setReferenceFrame(const QString & reference_frame); + void setAxesLength(float length); + void setAxesRadius(float radius); +}; + +#endif // RVIZ_DEFAULT_PLUGINS__PAGE_OBJECTS__AXES_DISPLAY_PAGE_OBJECT_HPP_ diff --git a/rviz_rendering/include/rviz_rendering/objects/axes.hpp b/rviz_rendering/include/rviz_rendering/objects/axes.hpp index 9431a58ee..f7080b324 100644 --- a/rviz_rendering/include/rviz_rendering/objects/axes.hpp +++ b/rviz_rendering/include/rviz_rendering/objects/axes.hpp @@ -33,11 +33,13 @@ #include #include +#include #include #include #include "object.hpp" +#include "shape.hpp" #include "rviz_rendering/visibility_control.hpp" namespace Ogre @@ -51,8 +53,6 @@ class ColourValue; namespace rviz_rendering { -class Shape; - /** * \class Axes * \brief An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue @@ -68,10 +68,12 @@ class Axes : public Object * @param radius Radius of the axes */ RVIZ_RENDERING_PUBLIC - Axes( - Ogre::SceneManager * manager, Ogre::SceneNode * parent_node = NULL, float length = 1.0f, + explicit Axes( + Ogre::SceneManager * manager, + Ogre::SceneNode * parent_node = nullptr, + float length = 1.0f, float radius = 0.1f); - virtual ~Axes(); + ~Axes() override; /** * \brief Set the parameters on this object @@ -83,22 +85,22 @@ class Axes : public Object void set(float length, float radius); RVIZ_RENDERING_PUBLIC - virtual void setOrientation(const Ogre::Quaternion & orientation); + void setOrientation(const Ogre::Quaternion & orientation) override; RVIZ_RENDERING_PUBLIC - virtual void setPosition(const Ogre::Vector3 & position); + void setPosition(const Ogre::Vector3 & position) override; RVIZ_RENDERING_PUBLIC - virtual void setScale(const Ogre::Vector3 & scale); + void setScale(const Ogre::Vector3 & scale) override; RVIZ_RENDERING_PUBLIC - virtual void setColor(float r, float g, float b, float a); + void setColor(float r, float g, float b, float a) override; RVIZ_RENDERING_PUBLIC - virtual const Ogre::Vector3 & getPosition(); + const Ogre::Vector3 & getPosition() override; RVIZ_RENDERING_PUBLIC - virtual const Ogre::Quaternion & getOrientation(); + const Ogre::Quaternion & getOrientation() override; /** * \brief Get the scene node associated with this object @@ -110,16 +112,16 @@ class Axes : public Object * \brief Sets user data on all ogre objects we own */ RVIZ_RENDERING_PUBLIC - void setUserData(const Ogre::Any & data); + void setUserData(const Ogre::Any & data) override; RVIZ_RENDERING_PUBLIC - Shape * getXShape() {return x_axis_;} + Shape & getXShape() {return *x_axis_;} RVIZ_RENDERING_PUBLIC - Shape * getYShape() {return y_axis_;} + Shape & getYShape() {return *y_axis_;} RVIZ_RENDERING_PUBLIC - Shape * getZShape() {return z_axis_;} + Shape & getZShape() {return *z_axis_;} RVIZ_RENDERING_PUBLIC void setXColor(const Ogre::ColourValue & col); @@ -145,14 +147,14 @@ class Axes : public Object private: // prohibit copying Axes(const Axes & other) - : Object(0) {(void) other;} + : Object(nullptr) {(void) other;} Axes & operator=(const Axes & other) {(void) other; return *this;} Ogre::SceneNode * scene_node_; - Shape * x_axis_; ///< Cylinder for the X-axis - Shape * y_axis_; ///< Cylinder for the Y-axis - Shape * z_axis_; ///< Cylinder for the Z-axis + std::unique_ptr x_axis_; ///< Cylinder for the X-axis + std::unique_ptr y_axis_; ///< Cylinder for the Y-axis + std::unique_ptr z_axis_; ///< Cylinder for the Z-axis static const Ogre::ColourValue default_x_color_; static const Ogre::ColourValue default_y_color_; diff --git a/rviz_rendering/src/rviz_rendering/objects/axes.cpp b/rviz_rendering/src/rviz_rendering/objects/axes.cpp index 045e96b82..d473c9ce7 100644 --- a/rviz_rendering/src/rviz_rendering/objects/axes.cpp +++ b/rviz_rendering/src/rviz_rendering/objects/axes.cpp @@ -30,6 +30,7 @@ #include "rviz_rendering/objects/axes.hpp" +#include #include #include @@ -55,19 +56,15 @@ Axes::Axes( scene_node_ = parent_node->createChildSceneNode(); - x_axis_ = new Shape(Shape::Cylinder, scene_manager_, scene_node_); - y_axis_ = new Shape(Shape::Cylinder, scene_manager_, scene_node_); - z_axis_ = new Shape(Shape::Cylinder, scene_manager_, scene_node_); + x_axis_ = std::make_unique(Shape::Cylinder, scene_manager_, scene_node_); + y_axis_ = std::make_unique(Shape::Cylinder, scene_manager_, scene_node_); + z_axis_ = std::make_unique(Shape::Cylinder, scene_manager_, scene_node_); set(length, radius); } Axes::~Axes() { - delete x_axis_; - delete y_axis_; - delete z_axis_; - scene_manager_->destroySceneNode(scene_node_); } @@ -107,8 +104,7 @@ void Axes::setColor(float r, float g, float b, float a) (void) g; (void) b; (void) a; - // for now, do nothing - /// \todo should anything be done here? + // we have several colors, so "setColor" doesn't make sense - noop } const Ogre::Vector3 & Axes::getPosition()