From 6a3d446b342ed79f00cf9e0156566f22dd75c752 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Mon, 27 Apr 2020 11:20:49 +0200 Subject: [PATCH] clang-tidy fixes (#1494) * modernize-use-nullptr * modernize-redundant-void-arg * modernize-use-override * readability-redundant-smartptr-get * readability-container-size-empty * readability-simplify-boolean-expr * readability-named-parameter * llvm-namespace-comment * fix warnings and remove #pragmas explicitly disabling warnings * Travis: enable warnings --- .clang-tidy | 47 +++++++++++++++++++ .travis.yml | 11 +++-- CMakeLists.txt | 3 +- src/rviz/add_display_dialog.cpp | 10 ++-- src/rviz/config.cpp | 22 ++++----- src/rviz/default_plugin/axes_display.cpp | 17 ++----- src/rviz/default_plugin/camera_display.cpp | 13 +---- src/rviz/default_plugin/covariance_visual.cpp | 7 +-- src/rviz/default_plugin/depth_cloud_mld.cpp | 10 ++-- src/rviz/default_plugin/effort_display.cpp | 2 +- .../default_plugin/grid_cells_display.cpp | 15 ------ src/rviz/default_plugin/grid_display.cpp | 2 +- src/rviz/default_plugin/image_display.cpp | 14 ------ .../interactive_marker.cpp | 4 +- .../interactive_marker_control.cpp | 8 ++-- src/rviz/default_plugin/map_display.cpp | 8 ++-- src/rviz/default_plugin/marker_utils.cpp | 6 +-- .../default_plugin/markers/arrow_marker.cpp | 4 +- .../markers/line_list_marker.cpp | 4 +- .../markers/line_strip_marker.cpp | 4 +- .../markers/mesh_resource_marker.cpp | 6 +-- .../default_plugin/markers/points_marker.cpp | 2 +- .../default_plugin/markers/shape_marker.cpp | 6 +-- .../markers/text_view_facing_marker.cpp | 2 +- .../markers/triangle_list_marker.cpp | 4 +- src/rviz/default_plugin/path_display.cpp | 8 ++-- .../default_plugin/point_cloud_common.cpp | 8 ++-- .../default_plugin/pose_array_display.cpp | 4 +- src/rviz/default_plugin/pose_display.cpp | 6 +-- .../pose_with_covariance_display.cpp | 6 +-- src/rviz/default_plugin/tf_display.cpp | 38 +++++++-------- src/rviz/default_plugin/tools/focus_tool.cpp | 2 +- src/rviz/default_plugin/tools/point_tool.cpp | 2 +- src/rviz/default_plugin/tools/pose_tool.cpp | 6 +-- src/rviz/display.cpp | 14 +++--- src/rviz/display_factory.cpp | 6 +-- src/rviz/display_group.cpp | 18 +++---- src/rviz/displays_panel.cpp | 4 +- src/rviz/failed_tool.cpp | 2 +- src/rviz/failed_view_controller.cpp | 2 +- src/rviz/frame_manager.cpp | 2 +- src/rviz/frame_manager.h | 12 ----- ...rame_position_tracking_view_controller.cpp | 4 +- src/rviz/help_panel.cpp | 2 +- src/rviz/load_resource.cpp | 2 +- src/rviz/mesh_loader.cpp | 33 ++++++------- src/rviz/new_object_dialog.cpp | 2 +- src/rviz/ogre_helpers/axes.cpp | 2 +- src/rviz/ogre_helpers/camera_base.cpp | 2 +- src/rviz/ogre_helpers/line.cpp | 2 +- src/rviz/ogre_helpers/mesh_shape.cpp | 4 +- src/rviz/ogre_helpers/movable_text.cpp | 18 +++---- src/rviz/ogre_helpers/ogre_logging.cpp | 6 +-- .../ogre_render_queue_clearer.cpp | 2 +- src/rviz/ogre_helpers/orthographic.cpp | 2 +- src/rviz/ogre_helpers/point_cloud.cpp | 12 +++-- src/rviz/ogre_helpers/point_cloud.h | 23 --------- .../ogre_helpers/qt_ogre_render_window.cpp | 18 +++---- src/rviz/ogre_helpers/render_system.cpp | 45 +++++++----------- src/rviz/ogre_helpers/render_system.h | 11 ----- src/rviz/ogre_helpers/render_widget.cpp | 4 +- src/rviz/ogre_helpers/shape.cpp | 2 +- src/rviz/ogre_helpers/stl_loader.cpp | 2 +- src/rviz/panel_dock_widget.cpp | 2 +- src/rviz/preferences_dialog.cpp | 2 +- .../display_group_visibility_property.cpp | 4 +- .../display_visibility_property.cpp | 2 +- src/rviz/properties/editable_combo_box.cpp | 2 +- src/rviz/properties/property.cpp | 28 +++++------ .../properties/property_tree_delegate.cpp | 2 +- src/rviz/properties/property_tree_model.cpp | 10 ++-- src/rviz/properties/property_tree_widget.cpp | 2 +- src/rviz/properties/tf_frame_property.cpp | 2 +- src/rviz/render_panel.cpp | 16 +++---- src/rviz/robot/robot.cpp | 10 ++-- src/rviz/robot/robot.h | 2 + src/rviz/robot/robot_joint.cpp | 18 +++---- src/rviz/robot/robot_link.cpp | 36 +++++++------- src/rviz/robot/tf_link_updater.cpp | 2 +- src/rviz/screenshot_dialog.cpp | 2 +- src/rviz/selection/selection_handler.cpp | 11 +++-- src/rviz/selection/selection_manager.cpp | 17 +++---- src/rviz/tool_manager.cpp | 10 ++-- src/rviz/view_controller.cpp | 6 +-- src/rviz/view_manager.cpp | 12 ++--- src/rviz/views_panel.cpp | 4 +- src/rviz/visualization_frame.cpp | 34 +++++++------- src/rviz/visualization_manager.cpp | 10 ++-- src/rviz/visualizer_app.cpp | 10 ++-- src/test/marker_test.cpp | 4 +- src/test/mesh_marker_test.cpp | 2 +- src/test/new_display_dialog_test.cpp | 2 +- src/test/rviz_logo_marker.cpp | 2 +- src/test/uniform_string_stream_test.cpp | 2 +- 94 files changed, 391 insertions(+), 446 deletions(-) create mode 100644 .clang-tidy diff --git a/.clang-tidy b/.clang-tidy new file mode 100644 index 0000000000..accc916bf7 --- /dev/null +++ b/.clang-tidy @@ -0,0 +1,47 @@ +--- +Checks: '-*, + llvm-namespace-comment, + modernize-redundant-void-arg, + modernize-use-nullptr, + modernize-use-default, + modernize-use-override, + readability-named-parameter, + readability-redundant-smartptr-get, + readability-redundant-string-cstr, + readability-simplify-boolean-expr, + readability-container-size-empty, + ' +HeaderFilterRegex: '' +AnalyzeTemporaryDtors: false +CheckOptions: + - key: llvm-namespace-comment.ShortNamespaceLines + value: '10' + - key: llvm-namespace-comment.SpacesBeforeComments + value: '2' + - key: readability-braces-around-statements.ShortStatementLines + value: '2' + # type names + - key: readability-identifier-naming.ClassCase + value: CamelCase + - key: readability-identifier-naming.EnumCase + value: CamelCase + - key: readability-identifier-naming.UnionCase + value: CamelCase + # method names + - key: readability-identifier-naming.MethodCase + value: camelBack + # variable names + - key: readability-identifier-naming.VariableCase + value: lower_case + - key: readability-identifier-naming.ClassMemberSuffix + value: '_' + # const static or global variables are UPPER_CASE + - key: readability-identifier-naming.EnumConstantCase + value: UPPER_CASE + - key: readability-identifier-naming.StaticConstantCase + value: UPPER_CASE + - key: readability-identifier-naming.ClassConstantCase + value: UPPER_CASE + - key: readability-identifier-naming.GlobalVariableCase + value: UPPER_CASE +... diff --git a/.travis.yml b/.travis.yml index 0c93c008be..d2706ecd45 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,5 +1,5 @@ # This config file for Travis CI utilizes https://github.com/ros-planning/moveit_ci/ package. -sudo: required +os: linux dist: xenial # distro used by Travis, moveit_ci uses the docker image's distro services: - docker @@ -7,15 +7,20 @@ language: cpp cache: ccache compiler: gcc +notifications: + email: true + env: global: - ROS_DISTRO=melodic - ROS_REPO=ros + - CXXFLAGS="-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-strict-aliasing -Wno-sign-compare" - WARNINGS_OK=true - ABI_BASE_URL=https://ni.www.techfak.uni-bielefeld.de/abicheck/rviz-${ROS_DISTRO}.tar.gz - matrix: + + jobs: - TEST=catkin_lint - - TEST=abi + - TEST=abi,clang-tidy-fix before_script: - git clone -q --depth=1 https://github.com/ros-planning/moveit_ci.git .moveit_ci diff --git a/CMakeLists.txt b/CMakeLists.txt index c716e291fa..009db6aae5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -233,7 +233,8 @@ include_directories(SYSTEM ${urdfdom_headers_INCLUDE_DIRS} ) #catkin_lint: ignore_once external_directory -include_directories(src ${EXPORT_HEADER_DIR} ${catkin_INCLUDE_DIRS}) +include_directories(src ${EXPORT_HEADER_DIR}) +include_directories(SYSTEM ${catkin_INCLUDE_DIRS}) #### If gtk ends up being the best way to get the correct window #### position under X11, this is how to compile it in. diff --git a/src/rviz/add_display_dialog.cpp b/src/rviz/add_display_dialog.cpp index 9114f9c0e7..1268eaa04d 100644 --- a/src/rviz/add_display_dialog.cpp +++ b/src/rviz/add_display_dialog.cpp @@ -129,7 +129,7 @@ void getPluginGroups( const QMap &datatype_plugins, if ( datatype_plugins.contains( datatype ) ) { - if ( groups->size() == 0 || + if ( groups->empty() || !isSubtopic(groups->back().base_topic.toStdString(), topic.toStdString()) ) { @@ -282,7 +282,7 @@ void AddDisplayDialog::onTopicSelected( SelectionData *data ) void AddDisplayDialog::updateDisplay() { - SelectionData *data = NULL; + SelectionData *data = nullptr; if ( tab_widget_->currentIndex() == topic_tab_ ) { data = &topic_data_; @@ -373,7 +373,7 @@ void DisplayTypeTree::onCurrentItemChanged(QTreeWidgetItem *curr, { // If display is selected, populate selection data. Otherwise, clear data. SelectionData sd; - if ( curr->parent() != NULL ) + if ( curr->parent() != nullptr ) { // Leave topic and datatype blank sd.whats_this = curr->whatsThis( 0 ); @@ -477,7 +477,7 @@ void TopicDisplayWidget::onCurrentItemChanged( QTreeWidgetItem* curr ) sd.display_name = curr->text( 0 ); QComboBox *combo = qobject_cast( tree_->itemWidget( curr, 1 ) ); - if ( combo != NULL ) + if ( combo != nullptr ) { QString combo_text = combo->currentText(); if ( combo_text != "raw" ) @@ -622,4 +622,4 @@ QTreeWidgetItem* TopicDisplayWidget::insertItem( const QString &topic, return current; } -} // rviz +} // namespace rviz diff --git a/src/rviz/config.cpp b/src/rviz/config.cpp index d8f440f908..f1b990c91f 100644 --- a/src/rviz/config.cpp +++ b/src/rviz/config.cpp @@ -62,7 +62,7 @@ class Config::Node Config::Node::Node() : type_( Empty ) { - data_.map = NULL; + data_.map = nullptr; } Config::Node::~Node() @@ -80,7 +80,7 @@ void Config::Node::deleteData() default: break; } - data_.map = NULL; + data_.map = nullptr; } void Config::Node::setType( Config::Type new_type ) @@ -201,7 +201,7 @@ Config Config::mapMakeChild( const QString& key ) Config Config::mapGetChild( const QString& key ) const { - if( node_.get() == NULL || node_->type_ != Map ) + if( node_.get() == nullptr || node_->type_ != Map ) { return invalidConfig(); } @@ -292,7 +292,7 @@ bool Config::mapGetString( const QString& key, QString *value_out ) const void Config::makeValid() { - if( node_.get() == NULL ) + if( node_.get() == nullptr ) { node_.reset( new Node() ); } @@ -300,7 +300,7 @@ void Config::makeValid() bool Config::isValid() const { - return node_.get() != NULL; + return node_.get() != nullptr; } void Config::setValue( const QVariant& value ) @@ -347,7 +347,7 @@ Config::MapIterator Config::mapIterator() const // Create a new (invalid) iterator. Config::MapIterator iter; - if( node_.get() == NULL || node_->type_ != Map ) + if( node_.get() == nullptr || node_->type_ != Map ) { // Force the node to be invalid, since this node does not have a map. iter.node_.reset(); @@ -367,7 +367,7 @@ Config::MapIterator::MapIterator() void Config::MapIterator::advance() { - if( node_.get() == NULL || node_->type_ != Config::Map ) + if( node_.get() == nullptr || node_->type_ != Config::Map ) { iterator_valid_ = false; return; @@ -385,7 +385,7 @@ void Config::MapIterator::advance() bool Config::MapIterator::isValid() { - if( node_.get() == NULL || node_->type_ != Config::Map ) + if( node_.get() == nullptr || node_->type_ != Config::Map ) { iterator_valid_ = false; return false; @@ -402,7 +402,7 @@ bool Config::MapIterator::isValid() void Config::MapIterator::start() { - if( node_.get() == NULL || node_->type_ != Config::Map ) + if( node_.get() == nullptr || node_->type_ != Config::Map ) { iterator_valid_ = false; return; @@ -413,7 +413,7 @@ void Config::MapIterator::start() QString Config::MapIterator::currentKey() { - if( node_.get() == NULL || node_->type_ != Config::Map || !iterator_valid_ ) + if( node_.get() == nullptr || node_->type_ != Config::Map || !iterator_valid_ ) { iterator_valid_ = false; return QString(); @@ -423,7 +423,7 @@ QString Config::MapIterator::currentKey() Config Config::MapIterator::currentChild() { - if( node_.get() == NULL || node_->type_ != Config::Map || !iterator_valid_ ) + if( node_.get() == nullptr || node_->type_ != Config::Map || !iterator_valid_ ) { iterator_valid_ = false; return Config(); diff --git a/src/rviz/default_plugin/axes_display.cpp b/src/rviz/default_plugin/axes_display.cpp index e1f5c10d64..37d649d090 100644 --- a/src/rviz/default_plugin/axes_display.cpp +++ b/src/rviz/default_plugin/axes_display.cpp @@ -29,20 +29,9 @@ #include -#ifndef _WIN32 -# pragma GCC diagnostic push -# ifdef __clang__ -# pragma clang diagnostic ignored "-W#warnings" -# endif -#endif - #include #include -#ifndef _WIN32 -# pragma GCC diagnostic pop -#endif - #include "rviz/display_context.h" #include "rviz/frame_manager.h" #include "rviz/ogre_helpers/axes.h" @@ -56,11 +45,11 @@ namespace rviz AxesDisplay::AxesDisplay() : Display() - , axes_( 0 ) + , axes_( nullptr ) { frame_property_ = new TfFrameProperty( "Reference Frame", TfFrameProperty::FIXED_FRAME_STRING, "The TF frame these axes will use for their origin.", - this, NULL, true ); + this, nullptr, true ); length_property_ = new FloatProperty( "Length", 1.0, "Length of each axis, in meters.", @@ -82,7 +71,7 @@ void AxesDisplay::onInitialize() { frame_property_->setFrameManager( context_->getFrameManager() ); - axes_ = new Axes( scene_manager_, 0, length_property_->getFloat(), radius_property_->getFloat() ); + axes_ = new Axes( scene_manager_, nullptr, length_property_->getFloat(), radius_property_->getFloat() ); axes_->getSceneNode()->setVisible( isEnabled() ); } diff --git a/src/rviz/default_plugin/camera_display.cpp b/src/rviz/default_plugin/camera_display.cpp index d06fba7f1f..ed2b57d30a 100644 --- a/src/rviz/default_plugin/camera_display.cpp +++ b/src/rviz/default_plugin/camera_display.cpp @@ -29,13 +29,6 @@ #include -#ifndef _WIN32 -# pragma GCC diagnostic push -# ifdef __clang__ -# pragma clang diagnostic ignored "-W#warnings" -# endif -#endif - #include #include #include @@ -48,10 +41,6 @@ #include #include -#ifndef _WIN32 -# pragma GCC diagnostic pop -#endif - #include #include "rviz/bit_allocator.h" @@ -92,7 +81,7 @@ bool validateFloats(const sensor_msgs::CameraInfo& msg) CameraDisplay::CameraDisplay() : ImageDisplayBase() , texture_() - , render_panel_( 0 ) + , render_panel_( nullptr ) , caminfo_ok_( false ) , force_render_( false ) { diff --git a/src/rviz/default_plugin/covariance_visual.cpp b/src/rviz/default_plugin/covariance_visual.cpp index b18db9545b..e48601df1b 100644 --- a/src/rviz/default_plugin/covariance_visual.cpp +++ b/src/rviz/default_plugin/covariance_visual.cpp @@ -193,7 +193,7 @@ void radianScaleToMetricScaleBounded(Ogre::Real & radian_scale, float max_degree } -} +} // namespace const float CovarianceVisual::max_degrees = 89.0; @@ -292,10 +292,7 @@ void CovarianceVisual::setCovariance( const geometry_msgs::PoseWithCovariance& p } } - if(pose.covariance[14] <= 0 && pose.covariance[21] <= 0 && pose.covariance[28] <= 0 ) - pose_2d_ = true; - else - pose_2d_ = false; + pose_2d_ = pose.covariance[14] <= 0 && pose.covariance[21] <= 0 && pose.covariance[28] <= 0; updateOrientationVisibility(); diff --git a/src/rviz/default_plugin/depth_cloud_mld.cpp b/src/rviz/default_plugin/depth_cloud_mld.cpp index 372d45e3e5..ac7f8c6531 100644 --- a/src/rviz/default_plugin/depth_cloud_mld.cpp +++ b/src/rviz/default_plugin/depth_cloud_mld.cpp @@ -181,9 +181,9 @@ template sensor_msgs::PointCloud2Ptr cloud_msg = initPointCloud(); cloud_msg->data.resize(height * width * cloud_msg->point_step); - uint32_t* color_img_ptr = 0; + uint32_t* color_img_ptr = nullptr; - if (rgba_color_raw.size()) + if (!rgba_color_raw.empty()) color_img_ptr = &rgba_color_raw[0]; //////////////////////////////////////////////// @@ -258,9 +258,9 @@ template sensor_msgs::PointCloud2Ptr cloud_msg = initPointCloud(); cloud_msg->data.resize(height * width * cloud_msg->point_step * 2); - uint32_t* color_img_ptr = 0; + uint32_t* color_img_ptr = nullptr; - if (rgba_color_raw.size()) + if (!rgba_color_raw.empty()) color_img_ptr = &rgba_color_raw[0]; //////////////////////////////////////////////// @@ -581,4 +581,4 @@ void MultiLayerDepth::finalizingPointCloud(sensor_msgs::PointCloud2Ptr& point_cl point_cloud->row_step = point_cloud->point_step * point_cloud->width; } -} +} // namespace rviz diff --git a/src/rviz/default_plugin/effort_display.cpp b/src/rviz/default_plugin/effort_display.cpp index bd4cc20232..ef43d8c3a9 100644 --- a/src/rviz/default_plugin/effort_display.cpp +++ b/src/rviz/default_plugin/effort_display.cpp @@ -61,7 +61,7 @@ namespace rviz M_JointInfo::iterator it = joints_.find( joint ); if ( it == joints_.end() ) { - return NULL; + return nullptr; } return it->second; diff --git a/src/rviz/default_plugin/grid_cells_display.cpp b/src/rviz/default_plugin/grid_cells_display.cpp index 4b4dae04d1..af1fcabca3 100644 --- a/src/rviz/default_plugin/grid_cells_display.cpp +++ b/src/rviz/default_plugin/grid_cells_display.cpp @@ -28,26 +28,11 @@ */ #include - -#ifndef _WIN32 -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wpedantic" -# ifdef __clang__ -# pragma clang diagnostic ignored "-Wdeprecated-register" -# endif -# pragma GCC diagnostic ignored "-Woverloaded-virtual" -# pragma GCC diagnostic ignored "-Wunused-parameter" -#endif - #include #include #include #include -#ifndef _WIN32 -# pragma GCC diagnostic pop -#endif - #include "rviz/frame_manager.h" #include "rviz/ogre_helpers/arrow.h" #include "rviz/ogre_helpers/point_cloud.h" diff --git a/src/rviz/default_plugin/grid_display.cpp b/src/rviz/default_plugin/grid_display.cpp index 5f3f4c242f..6eb1a6170d 100644 --- a/src/rviz/default_plugin/grid_display.cpp +++ b/src/rviz/default_plugin/grid_display.cpp @@ -51,7 +51,7 @@ GridDisplay::GridDisplay() { frame_property_ = new TfFrameProperty( "Reference Frame", TfFrameProperty::FIXED_FRAME_STRING, "The TF frame this grid will use for its origin.", - this, 0, true ); + this, nullptr, true ); cell_count_property_ = new IntProperty( "Plane Cell Count", 10, "The number of cells to draw in the plane of the grid.", diff --git a/src/rviz/default_plugin/image_display.cpp b/src/rviz/default_plugin/image_display.cpp index aeb5983793..9d1478d513 100644 --- a/src/rviz/default_plugin/image_display.cpp +++ b/src/rviz/default_plugin/image_display.cpp @@ -29,16 +29,6 @@ #include -#ifndef _WIN32 -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wpedantic" -# ifdef __clang__ -# pragma clang diagnostic ignored "-Wdeprecated-register" -# endif -# pragma GCC diagnostic ignored "-Woverloaded-virtual" -# pragma GCC diagnostic ignored "-Wunused-parameter" -#endif - #include #include #include @@ -52,10 +42,6 @@ #include #include -#ifndef _WIN32 -# pragma GCC diagnostic pop -#endif - #include "rviz/display_context.h" #include "rviz/frame_manager.h" #include "rviz/render_panel.h" diff --git a/src/rviz/default_plugin/interactive_markers/interactive_marker.cpp b/src/rviz/default_plugin/interactive_markers/interactive_marker.cpp index f3960c3366..67d7be7568 100644 --- a/src/rviz/default_plugin/interactive_markers/interactive_marker.cpp +++ b/src/rviz/default_plugin/interactive_markers/interactive_marker.cpp @@ -103,7 +103,7 @@ bool InteractiveMarker::processMessage( const visualization_msgs::InteractiveMar name_ = message.name; description_ = message.description; - if ( message.controls.size() == 0 ) + if ( message.controls.empty() ) { Q_EMIT statusUpdate( StatusProperty::Ok, name_, "Marker empty."); return false; @@ -130,7 +130,7 @@ bool InteractiveMarker::processMessage( const visualization_msgs::InteractiveMar axes_->setOrientation(orientation_); axes_->set( scale_, scale_*0.05 ); - has_menu_ = message.menu_entries.size() > 0; + has_menu_ = !message.menu_entries.empty(); updateReferencePose(); diff --git a/src/rviz/default_plugin/interactive_markers/interactive_marker_control.cpp b/src/rviz/default_plugin/interactive_markers/interactive_marker_control.cpp index bf92d553d6..0a97d17f70 100644 --- a/src/rviz/default_plugin/interactive_markers/interactive_marker_control.cpp +++ b/src/rviz/default_plugin/interactive_markers/interactive_marker_control.cpp @@ -65,7 +65,7 @@ InteractiveMarkerControl::InteractiveMarkerControl( DisplayContext* context, Ogre::SceneNode *reference_node, InteractiveMarker *parent ) : mouse_dragging_(false) -, drag_viewport_( NULL ) +, drag_viewport_( nullptr ) , context_( context ) , reference_node_(reference_node) , control_frame_node_(reference_node_->createChildSceneNode()) @@ -91,7 +91,7 @@ void InteractiveMarkerControl::makeMarkers( const visualization_msgs::Interactiv continue; // ignore invalid markers // create a marker with the given type - MarkerBasePtr marker(createMarker(marker_msg_const.type, 0, context_, markers_node_)); + MarkerBasePtr marker(createMarker(marker_msg_const.type, nullptr, context_, markers_node_)); PointsMarkerPtr points_marker = boost::dynamic_pointer_cast(marker); if (points_marker) { @@ -973,7 +973,7 @@ void InteractiveMarkerControl::stopDragging( bool force ) { line_->setVisible(false); mouse_dragging_ = false; - drag_viewport_ = NULL; + drag_viewport_ = nullptr; parent_->stopDragging(); } } @@ -1446,4 +1446,4 @@ void InteractiveMarkerControl::addHighlightPass( S_MaterialPtr materials ) } } -} +} // namespace rviz diff --git a/src/rviz/default_plugin/map_display.cpp b/src/rviz/default_plugin/map_display.cpp index 1c9be901c8..0559e4f1af 100644 --- a/src/rviz/default_plugin/map_display.cpp +++ b/src/rviz/default_plugin/map_display.cpp @@ -66,7 +66,7 @@ class AlphaSetter: public Ogre::Renderable::Visitor : alpha_vec_( alpha, alpha, alpha, alpha ) {} - void visit( Ogre::Renderable *rend, ushort /*lodIndex*/, bool /*isDebug*/, Ogre::Any * /*pAny*/=0) + void visit( Ogre::Renderable *rend, ushort /*lodIndex*/, bool /*isDebug*/, Ogre::Any * /*pAny*/=nullptr) override { rend->setCustomParameter( ALPHA_PARAMETER, alpha_vec_ ); } @@ -76,7 +76,7 @@ class AlphaSetter: public Ogre::Renderable::Visitor Swatch::Swatch(MapDisplay* parent, unsigned int x, unsigned int y, unsigned int width, unsigned int height, float resolution) - : parent_(parent), manual_object_( NULL ), x_(x), y_(y), width_(width), height_(height) + : parent_(parent), manual_object_( nullptr ), x_(x), y_(y), width_(width), height_(height) { // Set up map material static int material_count = 0; @@ -714,7 +714,7 @@ void MapDisplay::showMap() swatches[i]->updateData(); Ogre::Pass* pass = swatches[i]->material_->getTechnique(0)->getPass(0); - Ogre::TextureUnitState* tex_unit = NULL; + Ogre::TextureUnitState* tex_unit = nullptr; if (pass->getNumTextureUnitStates() > 0) { tex_unit = pass->getTextureUnitState(0); @@ -753,7 +753,7 @@ void MapDisplay::updatePalette() for (unsigned i=0; i < swatches.size(); i++){ Ogre::Pass* pass = swatches[i]->material_->getTechnique(0)->getPass(0); - Ogre::TextureUnitState* palette_tex_unit = NULL; + Ogre::TextureUnitState* palette_tex_unit = nullptr; if( pass->getNumTextureUnitStates() > 1 ) { palette_tex_unit = pass->getTextureUnitState( 1 ); diff --git a/src/rviz/default_plugin/marker_utils.cpp b/src/rviz/default_plugin/marker_utils.cpp index 9508dc87fb..9bfd7b9154 100644 --- a/src/rviz/default_plugin/marker_utils.cpp +++ b/src/rviz/default_plugin/marker_utils.cpp @@ -219,7 +219,7 @@ void checkColor(const visualization_msgs::Marker& marker, std::stringstream& ss, void checkPointsArrow(const visualization_msgs::Marker& marker, std::stringstream& ss, ::ros::console::levels::Level& level) { - if(marker.points.size() != 0 && marker.points.size() != 2) + if(!marker.points.empty() && marker.points.size() != 2) { addSeparatorIfRequired(ss); ss << "Number of points for an ARROW marker should be either 0 or 2."; @@ -281,7 +281,7 @@ void checkPointsEmpty(const visualization_msgs::Marker& marker, std::stringstrea void checkColors(const visualization_msgs::Marker& marker, std::stringstream& ss, ::ros::console::levels::Level& level, unsigned int multiple) { - if(marker.colors.size() == 0) + if(marker.colors.empty()) { checkColor(marker, ss, level); return; @@ -350,7 +350,7 @@ void checkMeshEmpty(const visualization_msgs::Marker& marker, std::stringstream& } } -} +} // namespace bool checkMarkerMsg(const visualization_msgs::Marker& marker, MarkerDisplay* owner) { diff --git a/src/rviz/default_plugin/markers/arrow_marker.cpp b/src/rviz/default_plugin/markers/arrow_marker.cpp index 4e043f8af1..6f4da0c160 100644 --- a/src/rviz/default_plugin/markers/arrow_marker.cpp +++ b/src/rviz/default_plugin/markers/arrow_marker.cpp @@ -47,7 +47,7 @@ namespace rviz ArrowMarker::ArrowMarker( MarkerDisplay* owner, DisplayContext* context, Ogre::SceneNode* parent_node ) : MarkerBase( owner, context, parent_node ) - , arrow_( 0 ), last_arrow_set_from_points_(false) + , arrow_( nullptr ), last_arrow_set_from_points_(false) { child_scene_node_ = scene_node_->createChildSceneNode(); } @@ -137,4 +137,4 @@ S_MaterialPtr ArrowMarker::getMaterials() return materials; } -} +} // namespace rviz diff --git a/src/rviz/default_plugin/markers/line_list_marker.cpp b/src/rviz/default_plugin/markers/line_list_marker.cpp index 5fce4c721c..a20373700b 100644 --- a/src/rviz/default_plugin/markers/line_list_marker.cpp +++ b/src/rviz/default_plugin/markers/line_list_marker.cpp @@ -43,7 +43,7 @@ namespace rviz LineListMarker::LineListMarker(MarkerDisplay* owner, DisplayContext* context, Ogre::SceneNode* parent_node) : MarkerBase(owner, context, parent_node) -, lines_(0) +, lines_(nullptr) { } @@ -133,4 +133,4 @@ S_MaterialPtr LineListMarker::getMaterials() return materials; } -} +} // namespace rviz diff --git a/src/rviz/default_plugin/markers/line_strip_marker.cpp b/src/rviz/default_plugin/markers/line_strip_marker.cpp index b299b13a19..c81b04b028 100644 --- a/src/rviz/default_plugin/markers/line_strip_marker.cpp +++ b/src/rviz/default_plugin/markers/line_strip_marker.cpp @@ -45,7 +45,7 @@ namespace rviz LineStripMarker::LineStripMarker(MarkerDisplay* owner, DisplayContext* context, Ogre::SceneNode* parent_node) : MarkerBase(owner, context, parent_node) -, lines_(0) +, lines_(nullptr) { } @@ -135,4 +135,4 @@ S_MaterialPtr LineStripMarker::getMaterials() return materials; } -} +} // namespace rviz diff --git a/src/rviz/default_plugin/markers/mesh_resource_marker.cpp b/src/rviz/default_plugin/markers/mesh_resource_marker.cpp index e884139404..964a5c5747 100644 --- a/src/rviz/default_plugin/markers/mesh_resource_marker.cpp +++ b/src/rviz/default_plugin/markers/mesh_resource_marker.cpp @@ -51,7 +51,7 @@ namespace rviz MeshResourceMarker::MeshResourceMarker(MarkerDisplay* owner, DisplayContext* context, Ogre::SceneNode* parent_node) : MarkerBase(owner, context, parent_node) -, entity_(0) +, entity_(nullptr) { } @@ -66,7 +66,7 @@ void MeshResourceMarker::reset() if (entity_) { context_->getSceneManager()->destroyEntity(entity_); - entity_ = 0; + entity_ = nullptr; } @@ -253,4 +253,4 @@ S_MaterialPtr MeshResourceMarker::getMaterials() return materials; } -} +} // namespace rviz diff --git a/src/rviz/default_plugin/markers/points_marker.cpp b/src/rviz/default_plugin/markers/points_marker.cpp index ee9baa9d12..2dafabbc44 100644 --- a/src/rviz/default_plugin/markers/points_marker.cpp +++ b/src/rviz/default_plugin/markers/points_marker.cpp @@ -45,7 +45,7 @@ namespace rviz PointsMarker::PointsMarker(MarkerDisplay* owner, DisplayContext* context, Ogre::SceneNode* parent_node) : MarkerBase(owner, context, parent_node) -, points_(0) +, points_(nullptr) { } diff --git a/src/rviz/default_plugin/markers/shape_marker.cpp b/src/rviz/default_plugin/markers/shape_marker.cpp index 6750b17f80..0ee90200b0 100644 --- a/src/rviz/default_plugin/markers/shape_marker.cpp +++ b/src/rviz/default_plugin/markers/shape_marker.cpp @@ -46,7 +46,7 @@ ShapeMarker::ShapeMarker( MarkerDisplay* owner, DisplayContext* context, Ogre::SceneNode* parent_node ) : MarkerBase( owner, context, parent_node ) - , shape_( 0 ) + , shape_( nullptr ) { } @@ -61,7 +61,7 @@ void ShapeMarker::onNewMessage( const MarkerConstPtr& old_message, if (!shape_ || old_message->type != new_message->type) { delete shape_; - shape_ = 0; + shape_ = nullptr; Shape::Type shape_type = Shape::Cube; switch( new_message->type ) @@ -102,4 +102,4 @@ S_MaterialPtr ShapeMarker::getMaterials() return materials; } -} +} // namespace rviz diff --git a/src/rviz/default_plugin/markers/text_view_facing_marker.cpp b/src/rviz/default_plugin/markers/text_view_facing_marker.cpp index 4693d93ea9..0fc15ecf28 100644 --- a/src/rviz/default_plugin/markers/text_view_facing_marker.cpp +++ b/src/rviz/default_plugin/markers/text_view_facing_marker.cpp @@ -87,5 +87,5 @@ S_MaterialPtr TextViewFacingMarker::getMaterials() return materials; } -} +} // namespace rviz diff --git a/src/rviz/default_plugin/markers/triangle_list_marker.cpp b/src/rviz/default_plugin/markers/triangle_list_marker.cpp index ed09e74c5e..5926163f69 100644 --- a/src/rviz/default_plugin/markers/triangle_list_marker.cpp +++ b/src/rviz/default_plugin/markers/triangle_list_marker.cpp @@ -50,7 +50,7 @@ namespace rviz TriangleListMarker::TriangleListMarker(MarkerDisplay* owner, DisplayContext* context, Ogre::SceneNode* parent_node) : MarkerBase(owner, context, parent_node) -, manual_object_(0) +, manual_object_(nullptr) { } @@ -200,5 +200,5 @@ S_MaterialPtr TriangleListMarker::getMaterials() } -} +} // namespace rviz diff --git a/src/rviz/default_plugin/path_display.cpp b/src/rviz/default_plugin/path_display.cpp index db6f36bad6..5e9d983cc2 100644 --- a/src/rviz/default_plugin/path_display.cpp +++ b/src/rviz/default_plugin/path_display.cpp @@ -326,7 +326,7 @@ void PathDisplay::destroyObjects() { manual_object->clear(); scene_manager_->destroyManualObject( manual_object ); - manual_object = NULL; // ensure it doesn't get destroyed again + manual_object = nullptr; // ensure it doesn't get destroyed again } } @@ -337,7 +337,7 @@ void PathDisplay::destroyObjects() if( billboard_line ) { delete billboard_line; // also destroys the corresponding scene node - billboard_line = NULL; // ensure it doesn't get destroyed again + billboard_line = nullptr; // ensure it doesn't get destroyed again } } } @@ -398,8 +398,8 @@ void PathDisplay::processMessage( const nav_msgs::Path::ConstPtr& msg ) size_t bufferIndex = messages_received_ % buffer_length_property_->getInt(); LineStyle style = (LineStyle) style_property_->getOptionInt(); - Ogre::ManualObject* manual_object = NULL; - rviz::BillboardLine* billboard_line = NULL; + Ogre::ManualObject* manual_object = nullptr; + rviz::BillboardLine* billboard_line = nullptr; // Delete oldest element switch(style) diff --git a/src/rviz/default_plugin/point_cloud_common.cpp b/src/rviz/default_plugin/point_cloud_common.cpp index d0ef7ba0c9..9681a9626b 100644 --- a/src/rviz/default_plugin/point_cloud_common.cpp +++ b/src/rviz/default_plugin/point_cloud_common.cpp @@ -291,8 +291,8 @@ void PointCloudSelectionHandler::onDeselect(const Picked& obj) } PointCloudCommon::CloudInfo::CloudInfo() -: manager_(0) -, scene_node_(0) +: manager_(nullptr) +, scene_node_(nullptr) {} PointCloudCommon::CloudInfo::~CloudInfo() @@ -305,7 +305,7 @@ void PointCloudCommon::CloudInfo::clear() if ( scene_node_ ) { manager_->destroySceneNode( scene_node_ ); - scene_node_=0; + scene_node_=nullptr; } } @@ -315,7 +315,7 @@ PointCloudCommon::PointCloudCommon( Display* display ) , new_xyz_transformer_(false) , new_color_transformer_(false) , needs_retransform_(false) -, transformer_class_loader_(NULL) +, transformer_class_loader_(nullptr) , display_( display ) { selectable_property_ = new BoolProperty( "Selectable", true, diff --git a/src/rviz/default_plugin/pose_array_display.cpp b/src/rviz/default_plugin/pose_array_display.cpp index 6e6309a79b..dbe0f8e78c 100644 --- a/src/rviz/default_plugin/pose_array_display.cpp +++ b/src/rviz/default_plugin/pose_array_display.cpp @@ -69,10 +69,10 @@ namespace normalizeQuaternion( quaternion, q ); return q; } -} +} // namespace PoseArrayDisplay::PoseArrayDisplay() - : manual_object_( NULL ) + : manual_object_( nullptr ) { shape_property_ = new EnumProperty( "Shape", "Arrow (Flat)", "Shape to display the pose as.", this, SLOT( updateShapeChoice() ) ); diff --git a/src/rviz/default_plugin/pose_display.cpp b/src/rviz/default_plugin/pose_display.cpp index 05e4913b13..dcf20f4b4b 100644 --- a/src/rviz/default_plugin/pose_display.cpp +++ b/src/rviz/default_plugin/pose_display.cpp @@ -58,7 +58,7 @@ class PoseDisplaySelectionHandler: public SelectionHandler , display_( display ) {} - void createProperties( const Picked& /*obj*/, Property* parent_property ) + void createProperties( const Picked& /*obj*/, Property* parent_property ) override { Property* cat = new Property( "Pose " + display_->getName(), QVariant(), "", parent_property ); properties_.push_back( cat ); @@ -73,7 +73,7 @@ class PoseDisplaySelectionHandler: public SelectionHandler orientation_property_->setReadOnly( true ); } - void getAABBs( const Picked& /*obj*/, V_AABB& aabbs ) + void getAABBs( const Picked& /*obj*/, V_AABB& aabbs ) override { if( display_->pose_valid_ ) { @@ -97,7 +97,7 @@ class PoseDisplaySelectionHandler: public SelectionHandler // and before destroyProperties(), during which frame_property_, // position_property_, and orientation_property_ should be valid // pointers. - if( properties_.size() > 0 ) + if( !properties_.empty() ) { frame_property_->setStdString( message->header.frame_id ); position_property_->setVector( Ogre::Vector3( message->pose.position.x, diff --git a/src/rviz/default_plugin/pose_with_covariance_display.cpp b/src/rviz/default_plugin/pose_with_covariance_display.cpp index 00333c3556..c851e11233 100644 --- a/src/rviz/default_plugin/pose_with_covariance_display.cpp +++ b/src/rviz/default_plugin/pose_with_covariance_display.cpp @@ -63,7 +63,7 @@ class PoseWithCovarianceDisplaySelectionHandler: public SelectionHandler , display_( display ) {} - void createProperties( const Picked& /*obj*/, Property* parent_property ) + void createProperties( const Picked& /*obj*/, Property* parent_property ) override { Property* cat = new Property( "Pose " + display_->getName(), QVariant(), "", parent_property ); properties_.push_back( cat ); @@ -84,7 +84,7 @@ class PoseWithCovarianceDisplaySelectionHandler: public SelectionHandler covariance_orientation_property_->setReadOnly( true ); } - void getAABBs( const Picked& /*obj*/, V_AABB& aabbs ) + void getAABBs( const Picked& /*obj*/, V_AABB& aabbs ) override { if( display_->pose_valid_ ) { @@ -122,7 +122,7 @@ class PoseWithCovarianceDisplaySelectionHandler: public SelectionHandler // and before destroyProperties(), during which frame_property_, // position_property_, and orientation_property_ should be valid // pointers. - if( properties_.size() > 0 ) + if( !properties_.empty() ) { frame_property_->setStdString( message->header.frame_id ); position_property_->setVector( Ogre::Vector3( message->pose.pose.position.x, diff --git a/src/rviz/default_plugin/tf_display.cpp b/src/rviz/default_plugin/tf_display.cpp index 0a6376019d..e55dff87e9 100644 --- a/src/rviz/default_plugin/tf_display.cpp +++ b/src/rviz/default_plugin/tf_display.cpp @@ -56,10 +56,10 @@ class FrameSelectionHandler: public SelectionHandler { public: FrameSelectionHandler( FrameInfo* frame, TFDisplay* display, DisplayContext* context ); - virtual ~FrameSelectionHandler() {} + ~FrameSelectionHandler() override {} - virtual void createProperties( const Picked& obj, Property* parent_property ); - virtual void destroyProperties( const Picked& obj, Property* parent_property ); + void createProperties( const Picked& obj, Property* parent_property ) override; + void destroyProperties( const Picked& obj, Property* parent_property ) override; bool getEnabled(); void setEnabled( bool enabled ); @@ -81,11 +81,11 @@ FrameSelectionHandler::FrameSelectionHandler(FrameInfo* frame, TFDisplay* displa : SelectionHandler( context ) , frame_( frame ) , display_( display ) - , category_property_( NULL ) - , enabled_property_( NULL ) - , parent_property_( NULL ) - , position_property_( NULL ) - , orientation_property_( NULL ) + , category_property_( nullptr ) + , enabled_property_( nullptr ) + , parent_property_( nullptr ) + , position_property_( nullptr ) + , orientation_property_( nullptr ) { } @@ -108,11 +108,11 @@ void FrameSelectionHandler::createProperties( const Picked& /*obj*/, Property* void FrameSelectionHandler::destroyProperties( const Picked& /*obj*/, Property* /*parent_property*/ ) { delete category_property_; // This deletes its children as well. - category_property_ = NULL; - enabled_property_ = NULL; - parent_property_ = NULL; - position_property_ = NULL; - orientation_property_ = NULL; + category_property_ = nullptr; + enabled_property_ = nullptr; + parent_property_ = nullptr; + position_property_ = nullptr; + orientation_property_ = nullptr; } bool FrameSelectionHandler::getEnabled() @@ -346,7 +346,7 @@ FrameInfo* TFDisplay::getFrameInfo( const std::string& frame ) M_FrameInfo::iterator it = frames_.find( frame ); if ( it == frames_.end() ) { - return NULL; + return nullptr; } return it->second; @@ -498,7 +498,7 @@ void TFDisplay::updateFrame( FrameInfo* frame ) // Check last received time so we can grey out/fade out frames that have stopped being published ros::Time latest_time; - tf->getLatestCommonTime( fixed_frame_.toStdString(), frame->name_, latest_time, 0 ); + tf->getLatestCommonTime( fixed_frame_.toStdString(), frame->name_, latest_time, nullptr ); if(( latest_time != frame->last_time_to_fixed_ ) || ( latest_time == ros::Time() )) @@ -737,13 +737,13 @@ void TFDisplay::reset() FrameInfo::FrameInfo( TFDisplay* display ) : display_( display ) - , axes_( NULL ) + , axes_( nullptr ) , axes_coll_( 0 ) - , parent_arrow_( NULL ) - , name_text_( NULL ) + , parent_arrow_( nullptr ) + , name_text_( nullptr ) , distance_to_parent_( 0.0f ) , arrow_orientation_(Ogre::Quaternion::IDENTITY) - , tree_property_( NULL ) + , tree_property_( nullptr ) {} void FrameInfo::updateVisibilityFromFrame() diff --git a/src/rviz/default_plugin/tools/focus_tool.cpp b/src/rviz/default_plugin/tools/focus_tool.cpp index 8e9074fe22..85bf792df1 100644 --- a/src/rviz/default_plugin/tools/focus_tool.cpp +++ b/src/rviz/default_plugin/tools/focus_tool.cpp @@ -107,7 +107,7 @@ int FocusTool::processMouseEvent( ViewportMouseEvent& event ) return flags; } -} +} // namespace rviz #include PLUGINLIB_EXPORT_CLASS( rviz::FocusTool, rviz::Tool ) diff --git a/src/rviz/default_plugin/tools/point_tool.cpp b/src/rviz/default_plugin/tools/point_tool.cpp index 3f5f0ee542..be197aa4ec 100644 --- a/src/rviz/default_plugin/tools/point_tool.cpp +++ b/src/rviz/default_plugin/tools/point_tool.cpp @@ -136,7 +136,7 @@ int PointTool::processMouseEvent( ViewportMouseEvent& event ) return flags; } -} +} // namespace rviz #include PLUGINLIB_EXPORT_CLASS( rviz::PointTool, rviz::Tool ) diff --git a/src/rviz/default_plugin/tools/pose_tool.cpp b/src/rviz/default_plugin/tools/pose_tool.cpp index 5efed334e0..91dda4856b 100644 --- a/src/rviz/default_plugin/tools/pose_tool.cpp +++ b/src/rviz/default_plugin/tools/pose_tool.cpp @@ -45,7 +45,7 @@ namespace rviz PoseTool::PoseTool() : Tool() - , arrow_( NULL ) + , arrow_( nullptr ) { } @@ -56,7 +56,7 @@ PoseTool::~PoseTool() void PoseTool::onInitialize() { - arrow_ = new Arrow( scene_manager_, NULL, 2.0f, 0.2f, 0.5f, 0.35f ); + arrow_ = new Arrow( scene_manager_, nullptr, 2.0f, 0.2f, 0.5f, 0.35f ); arrow_->setColor( 0.0f, 1.0f, 0.0f, 1.0f ); arrow_->getSceneNode()->setVisible( false ); } @@ -140,5 +140,5 @@ int PoseTool::processMouseEvent( ViewportMouseEvent& event ) return flags; } -} +} // namespace rviz diff --git a/src/rviz/display.cpp b/src/rviz/display.cpp index ca65e5314c..88198a98ba 100644 --- a/src/rviz/display.cpp +++ b/src/rviz/display.cpp @@ -54,13 +54,13 @@ namespace rviz { Display::Display() - : context_( 0 ) - , scene_node_( NULL ) - , status_( 0 ) + : context_( nullptr ) + , scene_node_( nullptr ) + , status_( nullptr ) , initialized_( false ) , visibility_bits_( 0xFFFFFFFF ) - , associated_widget_( NULL ) - , associated_widget_panel_( NULL ) + , associated_widget_( nullptr ) + , associated_widget_panel_( nullptr ) { // Needed for timeSignal (see header) to work across threads qRegisterMetaType(); @@ -381,13 +381,13 @@ void Display::setAssociatedWidget( QWidget* widget ) } else { - associated_widget_panel_ = NULL; + associated_widget_panel_ = nullptr; associated_widget_->setWindowTitle( getName() ); } } else { - associated_widget_panel_ = NULL; + associated_widget_panel_ = nullptr; } } diff --git a/src/rviz/display_factory.cpp b/src/rviz/display_factory.cpp index 0128e8cc42..df956d158f 100644 --- a/src/rviz/display_factory.cpp +++ b/src/rviz/display_factory.cpp @@ -78,7 +78,7 @@ QSet DisplayFactory::getMessageTypes( const QString& class_id ) tinyxml2::XMLDocument document; document.LoadFile(xml_file.toStdString().c_str()); tinyxml2::XMLElement * config = document.RootElement(); - if (config == NULL) + if (config == nullptr) { ROS_ERROR("Skipping XML Document \"%s\" which had no Root Element. This likely means the XML is malformed or missing.", xml_file.toStdString().c_str()); return QSet(); @@ -97,7 +97,7 @@ QSet DisplayFactory::getMessageTypes( const QString& class_id ) } tinyxml2::XMLElement* library = config; - while ( library != NULL) + while ( library != nullptr) { tinyxml2::XMLElement* class_element = library->FirstChildElement("class"); while (class_element) @@ -105,7 +105,7 @@ QSet DisplayFactory::getMessageTypes( const QString& class_id ) std::string derived_class = class_element->Attribute("type"); std::string current_class_id; - if(class_element->Attribute("name") != NULL) + if(class_element->Attribute("name") != nullptr) { current_class_id = class_element->Attribute("name"); ROS_DEBUG("XML file specifies lookup name (i.e. magic name) = %s.", current_class_id.c_str()); diff --git a/src/rviz/display_group.cpp b/src/rviz/display_group.cpp index 0c461815bd..d7b8ebb009 100644 --- a/src/rviz/display_group.cpp +++ b/src/rviz/display_group.cpp @@ -153,7 +153,7 @@ void DisplayGroup::save( Config config ) const void DisplayGroup::removeAllDisplays() { - if(displays_.size() == 0) + if(displays_.empty()) return; int num_non_display_children = Display::numChildren(); @@ -166,8 +166,8 @@ void DisplayGroup::removeAllDisplays() { Display* child = displays_.takeAt( i ); Q_EMIT displayRemoved( child ); - child->setParent( NULL ); // prevent child destructor from calling getParent()->takeChild(). - child->setModel( NULL ); + child->setParent( nullptr ); // prevent child destructor from calling getParent()->takeChild(). + child->setModel( nullptr ); child_indexes_valid_ = false; delete child; } @@ -180,7 +180,7 @@ void DisplayGroup::removeAllDisplays() Display* DisplayGroup::takeDisplay( Display* child ) { - Display* result = NULL; + Display* result = nullptr; int num_displays = displays_.size(); for( int i = 0; i < num_displays; i++ ) { @@ -192,8 +192,8 @@ Display* DisplayGroup::takeDisplay( Display* child ) } result = displays_.takeAt( i ); Q_EMIT displayRemoved( result ); - result->setParent( NULL ); - result->setModel( NULL ); + result->setParent( nullptr ); + result->setModel( nullptr ); child_indexes_valid_ = false; if( model_ ) { @@ -212,7 +212,7 @@ Display* DisplayGroup::getDisplayAt( int index ) const { return displays_.at( index ); } - return NULL; + return nullptr; } DisplayGroup* DisplayGroup::getGroupAt( int index ) const @@ -326,8 +326,8 @@ Property* DisplayGroup::takeChildAt( int index ) // printf(" displaygroup5 displays_.takeAt( %d ) ( index = %d )\n", disp_index, index ); Display* child = displays_.takeAt( disp_index ); Q_EMIT displayRemoved( child ); - child->setModel( NULL ); - child->setParent( NULL ); + child->setModel( nullptr ); + child->setParent( nullptr ); child_indexes_valid_ = false; if( model_ ) { diff --git a/src/rviz/displays_panel.cpp b/src/rviz/displays_panel.cpp index 48012a3f16..ab2cc2ffda 100644 --- a/src/rviz/displays_panel.cpp +++ b/src/rviz/displays_panel.cpp @@ -153,7 +153,7 @@ void DisplaysPanel::onDuplicateDisplay() duplicated_displays.push_back(disp); } // make sure the newly duplicated displays are selected. - if (duplicated_displays.size() > 0) { + if (!duplicated_displays.empty()) { QModelIndex first = property_grid_->getModel()->indexOf(duplicated_displays.front()); QModelIndex last = property_grid_->getModel()->indexOf(duplicated_displays.back()); QItemSelection selection(first, last); @@ -205,7 +205,7 @@ void DisplaysPanel::onSelectionChanged() void DisplaysPanel::onRenameDisplay() { QList displays = property_grid_->getSelectedObjects(); - if( displays.size() == 0 ) + if( displays.empty() ) { return; } diff --git a/src/rviz/failed_tool.cpp b/src/rviz/failed_tool.cpp index 390a3c5e2a..3ce7f6f928 100644 --- a/src/rviz/failed_tool.cpp +++ b/src/rviz/failed_tool.cpp @@ -63,7 +63,7 @@ void FailedTool::save( Config config ) const void FailedTool::activate() { - QWidget* parent = NULL; + QWidget* parent = nullptr; if( context_->getWindowManager() ) { parent = context_->getWindowManager()->getParentWindow(); diff --git a/src/rviz/failed_view_controller.cpp b/src/rviz/failed_view_controller.cpp index 957b33f2e2..c7637b7dbc 100644 --- a/src/rviz/failed_view_controller.cpp +++ b/src/rviz/failed_view_controller.cpp @@ -68,7 +68,7 @@ void FailedViewController::save( Config config ) const void FailedViewController::onActivate() { - QWidget* parent = NULL; + QWidget* parent = nullptr; if( context_->getWindowManager() ) { parent = context_->getWindowManager()->getParentWindow(); diff --git a/src/rviz/frame_manager.cpp b/src/rviz/frame_manager.cpp index 0271373ccb..efb9fd0c16 100644 --- a/src/rviz/frame_manager.cpp +++ b/src/rviz/frame_manager.cpp @@ -403,4 +403,4 @@ void FrameManager::messageFailedImpl( display->setStatusStd(StatusProperty::Error, status_name, status_text ); } -} +} // namespace rviz diff --git a/src/rviz/frame_manager.h b/src/rviz/frame_manager.h index 6d6422c4b9..c4c4114428 100644 --- a/src/rviz/frame_manager.h +++ b/src/rviz/frame_manager.h @@ -36,21 +36,9 @@ #include -#ifndef _WIN32 -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wpedantic" -# ifdef __clang__ -# pragma clang diagnostic ignored "-Wdeprecated-register" -# endif -#endif - #include #include -#ifndef _WIN32 -# pragma GCC diagnostic pop -#endif - #include #include diff --git a/src/rviz/frame_position_tracking_view_controller.cpp b/src/rviz/frame_position_tracking_view_controller.cpp index 8dca620446..93c29a463e 100644 --- a/src/rviz/frame_position_tracking_view_controller.cpp +++ b/src/rviz/frame_position_tracking_view_controller.cpp @@ -44,10 +44,10 @@ namespace rviz { FramePositionTrackingViewController::FramePositionTrackingViewController() - : target_scene_node_( NULL ) + : target_scene_node_( nullptr ) { target_frame_property_ = new TfFrameProperty( "Target Frame", TfFrameProperty::FIXED_FRAME_STRING, - "TF frame whose motion this view will follow.", this, NULL, true ); + "TF frame whose motion this view will follow.", this, nullptr, true ); } void FramePositionTrackingViewController::onInitialize() diff --git a/src/rviz/help_panel.cpp b/src/rviz/help_panel.cpp index 49a38eeff6..6031bdcf4d 100644 --- a/src/rviz/help_panel.cpp +++ b/src/rviz/help_panel.cpp @@ -44,7 +44,7 @@ namespace rviz HelpPanel::HelpPanel( QWidget* parent ) : Panel( parent ) - , browser_( NULL ) + , browser_( nullptr ) { QVBoxLayout* layout = new QVBoxLayout( this ); browser_ = new QTextBrowser(); diff --git a/src/rviz/load_resource.cpp b/src/rviz/load_resource.cpp index 1776168608..123d8f75fc 100644 --- a/src/rviz/load_resource.cpp +++ b/src/rviz/load_resource.cpp @@ -156,4 +156,4 @@ QCursor makeIconCursor( QPixmap icon, QString cache_key, bool fill_cache ) -} +} // namespace rviz diff --git a/src/rviz/mesh_loader.cpp b/src/rviz/mesh_loader.cpp index e52dcd3990..4c8b39729c 100644 --- a/src/rviz/mesh_loader.cpp +++ b/src/rviz/mesh_loader.cpp @@ -78,10 +78,10 @@ class ResourceIOStream : public Assimp::IOStream , pos_(res.data.get()) {} - ~ResourceIOStream() + ~ResourceIOStream() override {} - size_t Read(void* buffer, size_t size, size_t count) + size_t Read(void* buffer, size_t size, size_t count) override { size_t to_read = size * count; if (pos_ + to_read > res_.data.get() + res_.size) @@ -95,11 +95,11 @@ class ResourceIOStream : public Assimp::IOStream return to_read; } - size_t Write( const void* /*buffer*/, size_t /*size*/, size_t /*count*/) { ROS_BREAK(); return 0; } + size_t Write( const void* /*buffer*/, size_t /*size*/, size_t /*count*/) override { ROS_BREAK(); return 0; } - aiReturn Seek( size_t offset, aiOrigin origin) + aiReturn Seek( size_t offset, aiOrigin origin) override { - uint8_t* new_pos = 0; + uint8_t* new_pos = nullptr; switch (origin) { case aiOrigin_SET: @@ -124,17 +124,17 @@ class ResourceIOStream : public Assimp::IOStream return aiReturn_SUCCESS; } - size_t Tell() const + size_t Tell() const override { return pos_ - res_.data.get(); } - size_t FileSize() const + size_t FileSize() const override { return res_.size; } - void Flush() {} + void Flush() override {} private: resource_retriever::MemoryResource res_; @@ -148,12 +148,12 @@ class ResourceIOSystem : public Assimp::IOSystem { } - ~ResourceIOSystem() + ~ResourceIOSystem() override { } // Check whether a specific file exists - bool Exists(const char* file) const + bool Exists(const char* file) const override { // Ugly -- two retrievals where there should be one (Exists + Open) // resource_retriever needs a way of checking for existence @@ -172,15 +172,16 @@ class ResourceIOSystem : public Assimp::IOSystem } // Get the path delimiter character we'd like to see - char getOsSeparator() const + char getOsSeparator() const override { return '/'; } // ... and finally a method to open a custom stream - Assimp::IOStream* Open(const char* file, const char* mode = "rb") + Assimp::IOStream* Open(const char* file, const char* mode = "rb") override { ROS_ASSERT(mode == std::string("r") || mode == std::string("rb")); + (void)mode; // Ugly -- two retrievals where there should be one (Exists + Open) // resource_retriever needs a way of checking for existence @@ -191,13 +192,13 @@ class ResourceIOSystem : public Assimp::IOSystem } catch (resource_retriever::Exception& e) { - return 0; + return nullptr; } return new ResourceIOStream(res); } - void Close(Assimp::IOStream* stream); + void Close(Assimp::IOStream* stream) override; private: mutable resource_retriever::Retriever retriever_; @@ -229,7 +230,7 @@ void buildMesh( const aiScene* scene, const aiNode* node, { // Don't convert to y-up orientation, which is what the root node in // Assimp does - if (pnode->mParent != NULL) + if (pnode->mParent != nullptr) transform = pnode->mTransformation * transform; pnode = pnode->mParent; } @@ -720,4 +721,4 @@ Ogre::MeshPtr loadMeshFromResource(const std::string& resource_path) return Ogre::MeshPtr(); } -} +} // namespace rviz diff --git a/src/rviz/new_object_dialog.cpp b/src/rviz/new_object_dialog.cpp index b206b3dd15..a8a1966df0 100644 --- a/src/rviz/new_object_dialog.cpp +++ b/src/rviz/new_object_dialog.cpp @@ -264,5 +264,5 @@ void NewObjectDialog::accept() } } -} // rviz +} // namespace rviz diff --git a/src/rviz/ogre_helpers/axes.cpp b/src/rviz/ogre_helpers/axes.cpp index e4b74d6861..21375910c0 100644 --- a/src/rviz/ogre_helpers/axes.cpp +++ b/src/rviz/ogre_helpers/axes.cpp @@ -96,7 +96,7 @@ void Axes::setScale( const Ogre::Vector3& scale ) scene_node_->setScale( scale ); } -void Axes::setColor( float, float, float, float ) +void Axes::setColor( float /*r*/, float /*g*/, float /*b*/, float /*a*/) { // cannot change color globally, use set[XYZ]Color() instead } diff --git a/src/rviz/ogre_helpers/camera_base.cpp b/src/rviz/ogre_helpers/camera_base.cpp index 04f918fd1d..2bde0ab894 100644 --- a/src/rviz/ogre_helpers/camera_base.cpp +++ b/src/rviz/ogre_helpers/camera_base.cpp @@ -43,7 +43,7 @@ namespace rviz 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/src/rviz/ogre_helpers/line.cpp b/src/rviz/ogre_helpers/line.cpp index bd213cd095..95b3084fbb 100644 --- a/src/rviz/ogre_helpers/line.cpp +++ b/src/rviz/ogre_helpers/line.cpp @@ -149,4 +149,4 @@ void Line::setUserData( const Ogre::Any& data ) } -} +} // namespace rviz diff --git a/src/rviz/ogre_helpers/mesh_shape.cpp b/src/rviz/ogre_helpers/mesh_shape.cpp index d7eb97876c..1cb5e8351e 100644 --- a/src/rviz/ogre_helpers/mesh_shape.cpp +++ b/src/rviz/ogre_helpers/mesh_shape.cpp @@ -60,7 +60,7 @@ MeshShape::~MeshShape() void MeshShape::estimateVertexCount(size_t vcount) { - if (entity_ == NULL && started_ == false) + if (entity_ == nullptr && !started_) manual_object_->estimateVertexCount(vcount); } @@ -144,7 +144,7 @@ void MeshShape::clear() entity_->detachFromParent(); Ogre::MeshManager::getSingleton().remove(entity_->getMesh()->getName()); scene_manager_->destroyEntity( entity_ ); - entity_ = NULL; + entity_ = nullptr; } manual_object_->clear(); started_ = false; diff --git a/src/rviz/ogre_helpers/movable_text.cpp b/src/rviz/ogre_helpers/movable_text.cpp index bb974484dc..972d119182 100644 --- a/src/rviz/ogre_helpers/movable_text.cpp +++ b/src/rviz/ogre_helpers/movable_text.cpp @@ -77,16 +77,16 @@ MovableText::MovableText(const String &caption, const String &fontName, Real cha , mTimeUntilNextToggle(0) , mGlobalTranslation(0.0) , mLocalTranslation(0.0) -, mpCam(NULL) -, mpWin(NULL) -, mpFont(NULL) +, mpCam(nullptr) +, mpWin(nullptr) +, mpFont(nullptr) { static int count = 0; std::stringstream ss; ss << "MovableText" << count++; mName = ss.str(); - mRenderOp.vertexData = NULL; + mRenderOp.vertexData = nullptr; this->setFontName(mFontName); this->_setupGeometry(); } @@ -240,7 +240,7 @@ void MovableText::_setupGeometry() if (mRenderOp.vertexData) { delete mRenderOp.vertexData; - mRenderOp.vertexData = NULL; + mRenderOp.vertexData = nullptr; mUpdateColors = true; } @@ -252,7 +252,7 @@ void MovableText::_setupGeometry() if (!mRenderOp.vertexData) mRenderOp.vertexData = new VertexData(); - mRenderOp.indexData = 0; + mRenderOp.indexData = nullptr; mRenderOp.vertexData->vertexStart = 0; mRenderOp.vertexData->vertexCount = vertexCount; mRenderOp.operationType = RenderOperation::OT_TRIANGLE_LIST; @@ -467,7 +467,7 @@ void MovableText::_setupGeometry() mNeedUpdate = false; } -void MovableText::_updateColors(void) +void MovableText::_updateColors() { assert(mpFont); assert(!mpMaterial.isNull()); @@ -484,7 +484,7 @@ void MovableText::_updateColors(void) mUpdateColors = false; } -const Quaternion& MovableText::getWorldOrientation(void) const +const Quaternion& MovableText::getWorldOrientation() const { assert(mpCam); return const_cast (mpCam->getDerivedOrientation()); @@ -497,7 +497,7 @@ void MovableText::visitRenderables(Ogre::Renderable::Visitor* visitor, bool /*d } #endif -const Vector3& MovableText::getWorldPosition(void) const +const Vector3& MovableText::getWorldPosition() const { assert(mParentNode); return mParentNode->_getDerivedPosition(); diff --git a/src/rviz/ogre_helpers/ogre_logging.cpp b/src/rviz/ogre_helpers/ogre_logging.cpp index 67004f4cb7..fd093b6cc0 100644 --- a/src/rviz/ogre_helpers/ogre_logging.cpp +++ b/src/rviz/ogre_helpers/ogre_logging.cpp @@ -41,10 +41,10 @@ class RosLogListener: public Ogre::LogListener { public: RosLogListener(): min_lml(Ogre::LML_CRITICAL) {}; - virtual ~RosLogListener() {} + ~RosLogListener() override {} #if OGRE_VERSION >= ((1 << 16) | (8 << 8)) - virtual void messageLogged( const Ogre::String& message, Ogre::LogMessageLevel lml, bool /*maskDebug*/, const Ogre::String & /*logName*/, bool& skipThisMessage ) + void messageLogged( const Ogre::String& message, Ogre::LogMessageLevel lml, bool /*maskDebug*/, const Ogre::String & /*logName*/, bool& skipThisMessage ) override { if ( !skipThisMessage ) { @@ -100,7 +100,7 @@ void OgreLogging::configureLogging() { static RosLogListener ll; Ogre::LogManager* log_manager = Ogre::LogManager::getSingletonPtr(); - if( log_manager == NULL ) + if( log_manager == nullptr ) { log_manager = new Ogre::LogManager(); } diff --git a/src/rviz/ogre_helpers/ogre_render_queue_clearer.cpp b/src/rviz/ogre_helpers/ogre_render_queue_clearer.cpp index dc40ec0ac1..241b74111e 100644 --- a/src/rviz/ogre_helpers/ogre_render_queue_clearer.cpp +++ b/src/rviz/ogre_helpers/ogre_render_queue_clearer.cpp @@ -72,5 +72,5 @@ bool OgreRenderQueueClearer::frameStarted (const Ogre::FrameEvent & /*evt*/) return true; } -} +} // namespace rviz diff --git a/src/rviz/ogre_helpers/orthographic.cpp b/src/rviz/ogre_helpers/orthographic.cpp index 8be370e297..a8f34921dc 100644 --- a/src/rviz/ogre_helpers/orthographic.cpp +++ b/src/rviz/ogre_helpers/orthographic.cpp @@ -50,4 +50,4 @@ void buildScaledOrthoMatrix(Ogre::Matrix4& proj, float left, float right, float proj[3][3] = 1; } -} +} // namespace rviz diff --git a/src/rviz/ogre_helpers/point_cloud.cpp b/src/rviz/ogre_helpers/point_cloud.cpp index 8d2b713a45..7edc04e719 100644 --- a/src/rviz/ogre_helpers/point_cloud.cpp +++ b/src/rviz/ogre_helpers/point_cloud.cpp @@ -29,6 +29,7 @@ #include "point_cloud.h" #include +#include #include #include @@ -477,7 +478,7 @@ void PointCloud::addPoints(Point* points, uint32_t num_points) } } - float* vertices = 0; + float* vertices = nullptr; if (current_mode_supports_geometry_shader_) { vertices = g_point_vertices; @@ -512,9 +513,9 @@ void PointCloud::addPoints(Point* points, uint32_t num_points) PointCloudRenderablePtr rend; Ogre::HardwareVertexBufferSharedPtr vbuf; - void* vdata = 0; - Ogre::RenderOperation* op = 0; - float* fptr = 0; + void* vdata = nullptr; + Ogre::RenderOperation* op = nullptr; + float* fptr = nullptr; Ogre::AxisAlignedBox aabb; aabb.setNull(); @@ -601,6 +602,7 @@ void PointCloud::addPoints(Point* points, uint32_t num_points) ++fptr; ROS_ASSERT((uint8_t*)fptr <= (uint8_t*)vdata + rend->getBuffer()->getNumVertices() * vertex_size); + Q_UNUSED(vertex_size); } } @@ -847,7 +849,7 @@ void PointCloudRenderable::_notifyCurrentCamera(Ogre::Camera* camera) SimpleRenderable::_notifyCurrentCamera( camera ); } -Ogre::Real PointCloudRenderable::getBoundingRadius(void) const +Ogre::Real PointCloudRenderable::getBoundingRadius() const { return Ogre::Math::Sqrt(std::max(mBox.getMaximum().squaredLength(), mBox.getMinimum().squaredLength())); } diff --git a/src/rviz/ogre_helpers/point_cloud.h b/src/rviz/ogre_helpers/point_cloud.h index 93fcfed219..56096d4d78 100644 --- a/src/rviz/ogre_helpers/point_cloud.h +++ b/src/rviz/ogre_helpers/point_cloud.h @@ -30,16 +30,6 @@ #ifndef OGRE_TOOLS_OGRE_POINT_CLOUD_H #define OGRE_TOOLS_OGRE_POINT_CLOUD_H -#ifndef _WIN32 -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wpedantic" -# ifdef __clang__ -# pragma clang diagnostic ignored "-Wdeprecated-register" -# endif -# pragma GCC diagnostic ignored "-Woverloaded-virtual" -# pragma GCC diagnostic ignored "-Wunused-parameter" -#endif - #include #include #include @@ -51,10 +41,6 @@ #include #include -#ifndef _WIN32 -# pragma GCC diagnostic pop -#endif - #include #include @@ -82,17 +68,8 @@ class PointCloudRenderable : public Ogre::SimpleRenderable PointCloudRenderable(PointCloud* parent, int num_points, bool use_tex_coords); ~PointCloudRenderable(); -#ifndef _WIN32 -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Woverloaded-virtual" -#endif - Ogre::RenderOperation* getRenderOperation() { return &mRenderOp; } -#ifndef _WIN32 -# pragma GCC diagnostic pop -#endif - Ogre::HardwareVertexBufferSharedPtr getBuffer(); virtual Ogre::Real getBoundingRadius(void) const; diff --git a/src/rviz/ogre_helpers/qt_ogre_render_window.cpp b/src/rviz/ogre_helpers/qt_ogre_render_window.cpp index 7e4edc9bfb..c462fc8376 100644 --- a/src/rviz/ogre_helpers/qt_ogre_render_window.cpp +++ b/src/rviz/ogre_helpers/qt_ogre_render_window.cpp @@ -50,18 +50,18 @@ namespace rviz QtOgreRenderWindow::QtOgreRenderWindow( QWidget* parent ) : RenderWidget( RenderSystem::get(), parent ) - , viewport_( 0 ) + , viewport_( nullptr ) , ogre_root_( RenderSystem::get()->root() ) , ortho_scale_( 1.0f ) , auto_render_( true ) - , camera_( 0 ) + , camera_( nullptr ) , overlays_enabled_( true ) // matches the default of Ogre::Viewport. , background_color_( Ogre::ColourValue::Black ) // matches the default of Ogre::Viewport. , stereo_enabled_( false ) , rendering_stereo_( false ) - , left_camera_( 0 ) - , right_camera_( 0 ) - , right_viewport_( 0 ) + , left_camera_( nullptr ) + , right_camera_( nullptr ) + , right_viewport_( nullptr ) { render_window_->setVisible(true); render_window_->setAutoUpdated(true); @@ -103,7 +103,7 @@ void QtOgreRenderWindow::setupStereo() if (rendering_stereo_) { - right_viewport_ = render_window_->addViewport( NULL, 1 ); + right_viewport_ = render_window_->addViewport( nullptr, 1 ); #if OGRE_STEREO_ENABLE right_viewport_->setDrawBuffer(Ogre::CBT_BACK_RIGHT); viewport_->setDrawBuffer(Ogre::CBT_BACK_LEFT); @@ -121,7 +121,7 @@ void QtOgreRenderWindow::setupStereo() { render_window_->removeListener(this); render_window_->removeViewport(1); - right_viewport_ = NULL; + right_viewport_ = nullptr; #if OGRE_STEREO_ENABLE viewport_->setDrawBuffer(Ogre::CBT_BACK); @@ -129,10 +129,10 @@ void QtOgreRenderWindow::setupStereo() if (left_camera_) left_camera_->getSceneManager()->destroyCamera( left_camera_ ); - left_camera_ = NULL; + left_camera_ = nullptr; if (right_camera_) right_camera_->getSceneManager()->destroyCamera( right_camera_ ); - right_camera_ = NULL; + right_camera_ = nullptr; } } diff --git a/src/rviz/ogre_helpers/render_system.cpp b/src/rviz/ogre_helpers/render_system.cpp index eb01767a84..2b2bd1ee8e 100644 --- a/src/rviz/ogre_helpers/render_system.cpp +++ b/src/rviz/ogre_helpers/render_system.cpp @@ -50,23 +50,12 @@ #include // This dependency should be moved out of here, it is just used for a search path. #include -#ifndef _WIN32 -# pragma GCC diagnostic push -# ifdef __clang__ -# pragma clang diagnostic ignored "-W#warnings" -# endif -#endif - #include #include #if ((OGRE_VERSION_MAJOR == 1 && OGRE_VERSION_MINOR >= 9) || OGRE_VERSION_MAJOR >= 2 ) #include #endif -#ifndef _WIN32 -# pragma GCC diagnostic pop -#endif - #include "rviz/env_config.h" #include "rviz/ogre_helpers/ogre_logging.h" @@ -77,14 +66,14 @@ namespace rviz { -RenderSystem* RenderSystem::instance_ = 0; +RenderSystem* RenderSystem::instance_ = nullptr; int RenderSystem::force_gl_version_ = 0; bool RenderSystem::use_anti_aliasing_ = true; bool RenderSystem::force_no_stereo_ = false; RenderSystem* RenderSystem::get() { - if( instance_ == 0 ) + if( instance_ == nullptr ) { instance_ = new RenderSystem(); } @@ -110,7 +99,7 @@ void RenderSystem::forceNoStereo() } RenderSystem::RenderSystem() -: ogre_overlay_system_(NULL) +: ogre_overlay_system_(nullptr) , stereo_supported_(false) { OgreLogging::configureLogging(); @@ -144,14 +133,14 @@ void RenderSystem::setupDummyWindowId() #if defined(Q_OS_MAC) || defined(Q_OS_WIN) dummy_window_id_ = 0; #else - Display *display = XOpenDisplay(0); + Display *display = XOpenDisplay(nullptr); - if (display == NULL) { + if (display == nullptr) { ROS_WARN("$DISPLAY is invalid, falling back on default :0"); display = XOpenDisplay(":0"); - if (display == NULL) { + if (display == nullptr) { ROS_FATAL("Can't open default or :0 display. Try setting DISPLAY environment variable."); throw std::runtime_error("Can't open default or :0 display!\n"); } @@ -169,7 +158,7 @@ void RenderSystem::setupDummyWindowId() RootWindow( display, screen ), 0, 0, 1, 1, 0, 0, 0 ); - GLXContext context = glXCreateContext( display, visual, NULL, 1 ); + GLXContext context = glXCreateContext( display, visual, nullptr, 1 ); glXMakeCurrent( display, dummy_window_id_, context ); #endif @@ -246,7 +235,7 @@ void RenderSystem::setupRenderSystem() #endif // Look for the OpenGL one, which we require. - renderSys = NULL; + renderSys = nullptr; for( unsigned int i = 0; i < rsList->size(); i++ ) { renderSys = rsList->at( i ); @@ -256,7 +245,7 @@ void RenderSystem::setupRenderSystem() } } - if( renderSys == NULL ) + if( renderSys == nullptr ) { throw std::runtime_error( "Could not find the opengl rendering subsystem!\n" ); } @@ -375,7 +364,7 @@ Ogre::RenderWindow* RenderSystem::makeRenderWindow( static int windowCounter = 0; // Every RenderWindow needs a unique name, oy. Ogre::NameValuePairList params; - Ogre::RenderWindow *window = NULL; + Ogre::RenderWindow *window = nullptr; params["externalWindowHandle"] = Ogre::StringConverter::toString(window_id); params["parentWindowHandle"] = Ogre::StringConverter::toString(window_id); @@ -422,19 +411,19 @@ Ogre::RenderWindow* RenderSystem::makeRenderWindow( // without the stereo parameter. ogre_root_->detachRenderTarget(window); window->destroy(); - window = NULL; + window = nullptr; stream << "x"; is_stereo = false; } } } - if ( window == NULL ) + if ( window == nullptr ) { window = tryMakeRenderWindow( stream.str(), width, height, ¶ms, 100); } - if( window == NULL ) + if( window == nullptr ) { ROS_ERROR( "Unable to create the rendering window after 100 tries." ); assert(false); @@ -461,14 +450,14 @@ Ogre::RenderWindow* RenderSystem::tryMakeRenderWindow( const Ogre::NameValuePairList* params, int max_attempts ) { - Ogre::RenderWindow *window = NULL; + Ogre::RenderWindow *window = nullptr; int attempts = 0; #ifdef Q_WS_X11 old_error_handler = XSetErrorHandler( &checkBadDrawable ); #endif - while (window == NULL && (attempts++) < max_attempts) + while (window == nullptr && (attempts++) < max_attempts) { try { @@ -479,7 +468,7 @@ Ogre::RenderWindow* RenderSystem::tryMakeRenderWindow( if( x_baddrawable_error ) { ogre_root_->detachRenderTarget( window ); - window = NULL; + window = nullptr; x_baddrawable_error = false; } } @@ -487,7 +476,7 @@ Ogre::RenderWindow* RenderSystem::tryMakeRenderWindow( { std::cerr << "rviz::RenderSystem: error creating render window: " << ex.what() << std::endl; - window = NULL; + window = nullptr; } } diff --git a/src/rviz/ogre_helpers/render_system.h b/src/rviz/ogre_helpers/render_system.h index 88d348371f..0513c38e73 100644 --- a/src/rviz/ogre_helpers/render_system.h +++ b/src/rviz/ogre_helpers/render_system.h @@ -29,22 +29,11 @@ #ifndef RENDER_SYSTEM_H #define RENDER_SYSTEM_H -#ifndef _WIN32 -# pragma GCC diagnostic push -# ifdef __clang__ -# pragma clang diagnostic ignored "-W#warnings" -# endif -#endif - #include #include #include "rviz/rviz_export.h" -#ifndef _WIN32 -# pragma GCC diagnostic pop -#endif - namespace Ogre { class OverlaySystem; diff --git a/src/rviz/ogre_helpers/render_widget.cpp b/src/rviz/ogre_helpers/render_widget.cpp index 081caf9b38..08a1c84c58 100644 --- a/src/rviz/ogre_helpers/render_widget.cpp +++ b/src/rviz/ogre_helpers/render_widget.cpp @@ -95,7 +95,7 @@ RenderWidget::~RenderWidget() render_window_->destroy(); } - render_window_ = 0; + render_window_ = nullptr; } void RenderWidget::moveEvent(QMoveEvent *e) @@ -117,7 +117,7 @@ void RenderWidget::paintEvent(QPaintEvent *e) e->accept(); } -void RenderWidget::resizeEvent(QResizeEvent *) +void RenderWidget::resizeEvent(QResizeEvent * /*event*/) { if( render_window_ ) { diff --git a/src/rviz/ogre_helpers/shape.cpp b/src/rviz/ogre_helpers/shape.cpp index 9ea68465b8..681a3aa912 100644 --- a/src/rviz/ogre_helpers/shape.cpp +++ b/src/rviz/ogre_helpers/shape.cpp @@ -46,7 +46,7 @@ namespace rviz 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 nullptr; // the entity is initialized after the vertex data was specified std::string mesh_name; switch (type) diff --git a/src/rviz/ogre_helpers/stl_loader.cpp b/src/rviz/ogre_helpers/stl_loader.cpp index f960c4ee32..85dbdfe226 100644 --- a/src/rviz/ogre_helpers/stl_loader.cpp +++ b/src/rviz/ogre_helpers/stl_loader.cpp @@ -283,4 +283,4 @@ Ogre::MeshPtr STLLoader::toMesh(const std::string& name) return mesh; } -} +} // namespace ogre_tools diff --git a/src/rviz/panel_dock_widget.cpp b/src/rviz/panel_dock_widget.cpp index b361268ef9..4330e75ac8 100644 --- a/src/rviz/panel_dock_widget.cpp +++ b/src/rviz/panel_dock_widget.cpp @@ -131,7 +131,7 @@ void PanelDockWidget::closeEvent ( QCloseEvent * /*event*/ ) Q_EMIT closed(); } -void PanelDockWidget::onChildDestroyed( QObject* ) +void PanelDockWidget::onChildDestroyed( QObject* /*unused*/) { deleteLater(); } diff --git a/src/rviz/preferences_dialog.cpp b/src/rviz/preferences_dialog.cpp index 318511fede..585f10df47 100644 --- a/src/rviz/preferences_dialog.cpp +++ b/src/rviz/preferences_dialog.cpp @@ -98,5 +98,5 @@ void PreferencesDialog::accept() } } -} // rviz +} // namespace rviz diff --git a/src/rviz/properties/display_group_visibility_property.cpp b/src/rviz/properties/display_group_visibility_property.cpp index f6db1288ea..025e079c6b 100644 --- a/src/rviz/properties/display_group_visibility_property.cpp +++ b/src/rviz/properties/display_group_visibility_property.cpp @@ -122,7 +122,7 @@ void DisplayGroupVisibilityProperty::onDisplayRemoved( Display* display ) if ( it != disp_vis_props_.end() ) { Property* child = takeChild( it->second ); - child->setParent( NULL ); + child->setParent( nullptr ); delete child; disp_vis_props_.erase( display ); } @@ -133,4 +133,4 @@ DisplayGroupVisibilityProperty::~DisplayGroupVisibilityProperty() { } -} +} // namespace rviz diff --git a/src/rviz/properties/display_visibility_property.cpp b/src/rviz/properties/display_visibility_property.cpp index 1c2ba45d9a..9cf14d27de 100644 --- a/src/rviz/properties/display_visibility_property.cpp +++ b/src/rviz/properties/display_visibility_property.cpp @@ -105,4 +105,4 @@ Qt::ItemFlags DisplayVisibilityProperty::getViewFlags( int column ) const } -} +} // namespace rviz diff --git a/src/rviz/properties/editable_combo_box.cpp b/src/rviz/properties/editable_combo_box.cpp index 8887ed18c0..777c2403fb 100644 --- a/src/rviz/properties/editable_combo_box.cpp +++ b/src/rviz/properties/editable_combo_box.cpp @@ -48,7 +48,7 @@ EditableComboBox::EditableComboBox( QWidget* parent ) QString findMaxCommonPrefix( const QStringList& strings ) { - if( strings.size() == 0 ) + if( strings.empty() ) { return ""; } diff --git a/src/rviz/properties/property.cpp b/src/rviz/properties/property.cpp index 14e1238675..3331fc4b3a 100644 --- a/src/rviz/properties/property.cpp +++ b/src/rviz/properties/property.cpp @@ -46,7 +46,7 @@ namespace rviz class FailureProperty: public Property { public: - virtual Property* subProp( const QString& /*sub_name*/ ) { return this; } + Property* subProp( const QString& /*sub_name*/ ) override { return this; } }; /** @brief The property returned by subProp() when the requested @@ -60,9 +60,9 @@ Property::Property( const QString& name, const char *changed_slot, QObject* receiver ) : value_( default_value ) - , model_( 0 ) + , model_( nullptr ) , child_indexes_valid_( false ) - , parent_( 0 ) + , parent_( nullptr ) , description_( description ) , hidden_( false ) , is_read_only_( false ) @@ -73,7 +73,7 @@ Property::Property( const QString& name, { parent->addChild( this ); } - if( receiver == 0 ) + if( receiver == nullptr ) { receiver = parent; } @@ -94,7 +94,7 @@ Property::~Property() for( int i = children_.size() - 1; i >= 0; i-- ) { Property* child = children_.takeAt( i ); - child->setParent( NULL ); + child->setParent( nullptr ); delete child; } } @@ -117,7 +117,7 @@ void Property::removeChildren( int start_index, int count ) for( int i = start_index; i < start_index + count; i++ ) { Property* child = children_.at( i ); - child->setParent( NULL ); // prevent child destructor from calling getParent()->takeChild(). + child->setParent( nullptr ); // prevent child destructor from calling getParent()->takeChild(). delete child; } children_.erase( children_.begin() + start_index, children_.begin() + start_index + count ); @@ -188,7 +188,7 @@ Property* Property::subProp( const QString& sub_name ) // Print a useful error message showing the whole ancestry of this // property, but don't crash. QString ancestry = ""; - for( Property* prop = this; prop != NULL; prop = prop->getParent() ) + for( Property* prop = this; prop != nullptr; prop = prop->getParent() ) { ancestry = "\"" + prop->getName() + "\"->" + ancestry; } @@ -204,7 +204,7 @@ Property* Property::childAt( int index ) const { return childAtUnchecked( index ); } - return NULL; + return nullptr; } Property* Property::childAtUnchecked( int index ) const @@ -301,7 +301,7 @@ Qt::ItemFlags Property::getViewFlags( int column ) const bool Property::isAncestorOf( Property* possible_child ) const { Property* prop = possible_child->getParent(); - while( prop != NULL && prop != this ) + while( prop != nullptr && prop != this ) { prop = prop->getParent(); } @@ -317,22 +317,22 @@ Property* Property::takeChild( Property* child ) return takeChildAt( i ); } } - return NULL; + return nullptr; } Property* Property::takeChildAt( int index ) { if( index < 0 || index >= children_.size() ) { - return NULL; + return nullptr; } if( model_ ) { model_->beginRemove( this, index, 1 ); } Property* child = children_.takeAt( index ); - child->setModel( NULL ); - child->parent_ = NULL; + child->setModel( nullptr ); + child->parent_ = nullptr; child_indexes_valid_ = false; if( model_ ) { @@ -462,7 +462,7 @@ void Property::loadValue( const Config& config ) void Property::save( Config config ) const { // If there are child properties, save them in a map from names to children. - if( children_.size() > 0 ) + if( !children_.empty() ) { // If this property has child properties *and* a value itself, // save the value in a special map entry named "Value". diff --git a/src/rviz/properties/property_tree_delegate.cpp b/src/rviz/properties/property_tree_delegate.cpp index 93c6fe0553..059128c2cd 100644 --- a/src/rviz/properties/property_tree_delegate.cpp +++ b/src/rviz/properties/property_tree_delegate.cpp @@ -60,7 +60,7 @@ QWidget *PropertyTreeDelegate::createEditor( QWidget *parent, Property* prop = static_cast( index.internalPointer() ); if( !prop || prop->getReadOnly()) { - return 0; + return nullptr; } if( QWidget* editor = prop->createEditor( parent, option )) diff --git a/src/rviz/properties/property_tree_model.cpp b/src/rviz/properties/property_tree_model.cpp index afc4d645d2..1c6ccf4cca 100644 --- a/src/rviz/properties/property_tree_model.cpp +++ b/src/rviz/properties/property_tree_model.cpp @@ -155,11 +155,7 @@ bool PropertyTreeModel::setData( const QModelIndex& index, const QVariant& value return false; } - if( property->setValue( value )) - { - return true; - } - return false; + return property->setValue( value ); } /** @brief Override from QAbstractItemModel. Returns a @@ -172,12 +168,12 @@ QMimeData* PropertyTreeModel::mimeData( const QModelIndexList& indexes ) const { if( indexes.count() <= 0 ) { - return 0; + return nullptr; } QStringList types = mimeTypes(); if( types.isEmpty() ) { - return 0; + return nullptr; } QMimeData *data = new QMimeData(); QString format = types.at(0); diff --git a/src/rviz/properties/property_tree_widget.cpp b/src/rviz/properties/property_tree_widget.cpp index 900d85b673..e3b5dd297c 100644 --- a/src/rviz/properties/property_tree_widget.cpp +++ b/src/rviz/properties/property_tree_widget.cpp @@ -58,7 +58,7 @@ void PropertySelectionModel::setCurrentIndex(const QModelIndex &index, QItemSele PropertyTreeWidget::PropertyTreeWidget( QWidget* parent ) : QTreeView( parent ) - , model_( NULL ) + , model_( nullptr ) , splitter_handle_( new SplitterHandle( this )) { setItemDelegateForColumn( 1, new PropertyTreeDelegate( this )); diff --git a/src/rviz/properties/tf_frame_property.cpp b/src/rviz/properties/tf_frame_property.cpp index c8dbb40c97..62ea4afee0 100644 --- a/src/rviz/properties/tf_frame_property.cpp +++ b/src/rviz/properties/tf_frame_property.cpp @@ -47,7 +47,7 @@ TfFrameProperty::TfFrameProperty( const QString& name, const char *changed_slot, QObject* receiver ) : EditableEnumProperty( name, default_value, description, parent, changed_slot, receiver ) - , frame_manager_( NULL ) + , frame_manager_( nullptr ) , include_fixed_frame_string_( include_fixed_frame_string ) { // Parent class EditableEnumProperty has requestOptions() signal. diff --git a/src/rviz/render_panel.cpp b/src/rviz/render_panel.cpp index 0aa50c1734..3ae9cf0d46 100644 --- a/src/rviz/render_panel.cpp +++ b/src/rviz/render_panel.cpp @@ -50,13 +50,13 @@ RenderPanel::RenderPanel( QWidget* parent ) , mouse_x_( 0 ) , mouse_y_( 0 ) , focus_on_mouse_move_( true ) - , context_( 0 ) - , scene_manager_( 0 ) - , view_controller_( 0 ) + , context_( nullptr ) + , scene_manager_( nullptr ) + , view_controller_( nullptr ) , context_menu_visible_(false) //TODO(simonschmeisser) remove this in noetic , fake_mouse_move_event_timer_( new QTimer() ) - , default_camera_(0) + , default_camera_(nullptr) { setFocusPolicy(Qt::WheelFocus); setFocus( Qt::OtherFocusReason ); @@ -190,7 +190,7 @@ void RenderPanel::setViewController( ViewController* controller ) } else { - setCamera( NULL ); + setCamera( nullptr ); } } @@ -232,9 +232,9 @@ void RenderPanel::sceneManagerDestroyed( Ogre::SceneManager* destroyed_scene_man { if( destroyed_scene_manager == scene_manager_ ) { - scene_manager_ = NULL; - default_camera_ = NULL; - setCamera( NULL ); + scene_manager_ = nullptr; + default_camera_ = nullptr; + setCamera( nullptr ); } } diff --git a/src/rviz/robot/robot.cpp b/src/rviz/robot/robot.cpp index f001ea9fde..f2a44de12f 100644 --- a/src/rviz/robot/robot.cpp +++ b/src/rviz/robot/robot.cpp @@ -261,7 +261,7 @@ void Robot::load( const urdf::ModelInterface &urdf, bool visual, bool collision clear(); // the root link is discovered below. Set to NULL until found. - root_link_ = NULL; + root_link_ = nullptr; // Create properties for each link. // Properties are not added to display until changedLinkTreeStyle() is called (below). @@ -335,7 +335,7 @@ void Robot::unparentLinkProperties() M_NameToLink::iterator link_end = links_.end(); for ( ; link_it != link_end ; ++link_it ) { - link_it->second->setParentProperty(NULL); + link_it->second->setParentProperty(nullptr); } // remove joint properties from their parents @@ -343,7 +343,7 @@ void Robot::unparentLinkProperties() M_NameToJoint::iterator joint_end = joints_.end(); for ( ; joint_it != joint_end ; ++joint_it ) { - joint_it->second->setParentProperty(NULL); + joint_it->second->setParentProperty(nullptr); } } @@ -655,7 +655,7 @@ RobotLink* Robot::getLink( const std::string& name ) if ( it == links_.end() ) { ROS_WARN( "Link [%s] does not exist", name.c_str() ); - return NULL; + return nullptr; } return it->second; @@ -667,7 +667,7 @@ RobotJoint* Robot::getJoint( const std::string& name ) if ( it == joints_.end() ) { ROS_WARN( "Joint [%s] does not exist", name.c_str() ); - return NULL; + return nullptr; } return it->second; diff --git a/src/rviz/robot/robot.h b/src/rviz/robot/robot.h index 6dbe0c3695..2e4317b204 100644 --- a/src/rviz/robot/robot.h +++ b/src/rviz/robot/robot.h @@ -167,6 +167,8 @@ Q_OBJECT class LinkFactory { public: + virtual ~LinkFactory() = default; + virtual RobotLink* createLink( Robot* robot, const urdf::LinkConstSharedPtr& link, const std::string& parent_joint_name, diff --git a/src/rviz/robot/robot_joint.cpp b/src/rviz/robot/robot_joint.cpp index 42d32d162c..e67673e45c 100644 --- a/src/rviz/robot/robot_joint.cpp +++ b/src/rviz/robot/robot_joint.cpp @@ -51,19 +51,19 @@ RobotJoint::RobotJoint( Robot* robot, const urdf::JointConstSharedPtr& joint ) , child_link_name_( joint->child_link_name ) , has_decendent_links_with_geometry_( true ) , doing_set_checkbox_( false ) - , axes_( NULL ) - , axis_( NULL ) + , axes_( nullptr ) + , axis_( nullptr ) { joint_property_ = new Property( name_.c_str(), true, "", - NULL, + nullptr, SLOT( updateChildVisibility() ), this); joint_property_->setIcon( rviz::loadPixmap( "package://rviz/icons/classes/RobotJoint.png" ) ); - details_ = new Property( "Details", QVariant(), "", NULL); + details_ = new Property( "Details", QVariant(), "", nullptr); axes_property_ = new Property( "Show Axes", @@ -224,11 +224,11 @@ RobotJoint* RobotJoint::getParentJoint() { RobotLink* parent_link = robot_->getLink(parent_link_name_); if (!parent_link) - return NULL; + return nullptr; const std::string& parent_joint_name = parent_link->getParentJointName(); if (parent_joint_name.empty()) - return NULL; + return nullptr; return robot_->getJoint(parent_joint_name); } @@ -342,7 +342,7 @@ bool RobotJoint::getEnabled() const bool RobotJoint::styleIsTree() const { - return details_->getParent() != NULL; + return details_->getParent() != nullptr; } void RobotJoint::updateChildVisibility() @@ -400,7 +400,7 @@ void RobotJoint::updateAxes() if( axes_ ) { delete axes_; - axes_ = NULL; + axes_ = nullptr; } } } @@ -430,7 +430,7 @@ void RobotJoint::updateAxis() if( axis_ ) { delete axis_; - axis_ = NULL; + axis_ = nullptr; } } } diff --git a/src/rviz/robot/robot_link.cpp b/src/rviz/robot/robot_link.cpp index 36ce7b213c..59b255e29d 100644 --- a/src/rviz/robot/robot_link.cpp +++ b/src/rviz/robot/robot_link.cpp @@ -76,13 +76,13 @@ class RobotLinkSelectionHandler : public SelectionHandler { public: RobotLinkSelectionHandler( RobotLink* link, DisplayContext* context ); - virtual ~RobotLinkSelectionHandler(); + ~RobotLinkSelectionHandler() override; - virtual void createProperties( const Picked& obj, Property* parent_property ); - virtual void updateProperties(); + void createProperties( const Picked& obj, Property* parent_property ) override; + void updateProperties() override; - virtual void preRenderPass(uint32_t pass); - virtual void postRenderPass(uint32_t pass); + void preRenderPass(uint32_t pass) override; + void postRenderPass(uint32_t pass) override; private: RobotLink* link_; @@ -163,20 +163,20 @@ RobotLink::RobotLink( Robot* robot, , context_( robot->getDisplayContext() ) , name_( link->name ) , parent_joint_name_( parent_joint_name ) -, visual_node_( NULL ) -, collision_node_( NULL ) -, trail_( NULL ) -, axes_( NULL ) +, visual_node_( nullptr ) +, collision_node_( nullptr ) +, trail_( nullptr ) +, axes_( nullptr ) , material_alpha_( 1.0 ) , robot_alpha_(1.0) , only_render_depth_(false) , is_selectable_( true ) , using_color_( false ) { - link_property_ = new Property( link->name.c_str(), true, "", NULL, SLOT( updateVisibility() ), this ); + link_property_ = new Property( link->name.c_str(), true, "", nullptr, SLOT( updateVisibility() ), this ); link_property_->setIcon( rviz::loadPixmap( "package://rviz/icons/classes/RobotLink.png" ) ); - details_ = new Property( "Details", QVariant(), "", NULL); + details_ = new Property( "Details", QVariant(), "", nullptr); alpha_property_ = new FloatProperty( "Alpha", 1, "Amount of transparency to apply to this link.", @@ -521,7 +521,7 @@ Ogre::MaterialPtr RobotLink::getMaterialForLink( const urdf::LinkConstSharedPtr& void RobotLink::createEntityForGeometryElement(const urdf::LinkConstSharedPtr& link, const urdf::Geometry& geom, const urdf::MaterialSharedPtr& material, const urdf::Pose& origin, Ogre::SceneNode* scene_node, Ogre::Entity*& entity) { - entity = NULL; // default in case nothing works. + entity = nullptr; // default in case nothing works. Ogre::SceneNode* offset_node = scene_node->createChildSceneNode(); static unsigned count = 0; @@ -677,7 +677,7 @@ void RobotLink::createCollision(const urdf::LinkConstSharedPtr& link) urdf::CollisionSharedPtr collision = *vi; if( collision && collision->geometry ) { - Ogre::Entity* collision_mesh = NULL; + Ogre::Entity* collision_mesh = nullptr; createEntityForGeometryElement( link, *collision->geometry, urdf::MaterialSharedPtr(), collision->origin, collision_node_, collision_mesh ); if( collision_mesh ) { @@ -690,7 +690,7 @@ void RobotLink::createCollision(const urdf::LinkConstSharedPtr& link) if( !valid_collision_found && link->collision && link->collision->geometry ) { - Ogre::Entity* collision_mesh = NULL; + Ogre::Entity* collision_mesh = nullptr; createEntityForGeometryElement( link, *link->collision->geometry, urdf::MaterialSharedPtr(), link->collision->origin, collision_node_, collision_mesh ); if( collision_mesh ) { @@ -734,7 +734,7 @@ void RobotLink::createVisual(const urdf::LinkConstSharedPtr& link ) urdf::VisualSharedPtr visual = *vi; if( visual && visual->geometry ) { - Ogre::Entity* visual_mesh = NULL; + Ogre::Entity* visual_mesh = nullptr; createEntityForGeometryElement( link, *visual->geometry, visual->material, visual->origin, visual_node_, visual_mesh ); if( visual_mesh ) { @@ -747,7 +747,7 @@ void RobotLink::createVisual(const urdf::LinkConstSharedPtr& link ) if( !valid_visual_found && link->visual && link->visual->geometry ) { - Ogre::Entity* visual_mesh = NULL; + Ogre::Entity* visual_mesh = nullptr; createEntityForGeometryElement( link, *link->visual->geometry, link->visual->material, link->visual->origin, visual_node_, visual_mesh ); if( visual_mesh ) { @@ -802,7 +802,7 @@ void RobotLink::updateTrail() if( trail_ ) { scene_manager_->destroyRibbonTrail( trail_ ); - trail_ = NULL; + trail_ = nullptr; } } } @@ -828,7 +828,7 @@ void RobotLink::updateAxes() if( axes_ ) { delete axes_; - axes_ = NULL; + axes_ = nullptr; } } } diff --git a/src/rviz/robot/tf_link_updater.cpp b/src/rviz/robot/tf_link_updater.cpp index 761c51ef6c..f4d553c7b4 100644 --- a/src/rviz/robot/tf_link_updater.cpp +++ b/src/rviz/robot/tf_link_updater.cpp @@ -83,4 +83,4 @@ void TFLinkUpdater::setLinkStatus(StatusLevel level, const std::string& link_nam } } -} +} // namespace rviz diff --git a/src/rviz/screenshot_dialog.cpp b/src/rviz/screenshot_dialog.cpp index 54c7058235..076626267d 100644 --- a/src/rviz/screenshot_dialog.cpp +++ b/src/rviz/screenshot_dialog.cpp @@ -46,7 +46,7 @@ namespace rviz { ScreenshotDialog::ScreenshotDialog( QWidget* main_window, QWidget* render_window, const QString& default_save_dir ) - : QWidget( NULL ) // This should be a top-level window to act like a dialog. + : QWidget( nullptr ) // This should be a top-level window to act like a dialog. , main_window_( main_window ) , render_window_( render_window ) , save_full_window_( false ) diff --git a/src/rviz/selection/selection_handler.cpp b/src/rviz/selection/selection_handler.cpp index fa6a2d935d..722b3ec64f 100644 --- a/src/rviz/selection/selection_handler.cpp +++ b/src/rviz/selection/selection_handler.cpp @@ -61,7 +61,7 @@ SelectionHandler::~SelectionHandler() for (; it != end; ++it) { Ogre::MovableObject* m = *it; - m->setListener(0); + m->setListener(nullptr); } while (!boxes_.empty()) @@ -127,7 +127,7 @@ void SelectionHandler::addTrackedObject(Ogre::MovableObject* object) void SelectionHandler::removeTrackedObject(Ogre::MovableObject* object) { tracked_objects_.erase(object); - object->setListener(0); + object->setListener(nullptr); updateTrackedBoxes(); } @@ -179,8 +179,8 @@ void SelectionHandler::destroyProperties( const Picked& /*obj*/, Property* /*p void SelectionHandler::createBox(const std::pair& handles, const Ogre::AxisAlignedBox& aabb, const std::string& material_name) { - Ogre::WireBoundingBox* box = 0; - Ogre::SceneNode* node = 0; + Ogre::WireBoundingBox* box = nullptr; + Ogre::SceneNode* node = nullptr; M_HandleToBox::iterator it = boxes_.find(handles); if (it == boxes_.end()) @@ -191,6 +191,7 @@ void SelectionHandler::createBox(const std::pair& ha bool inserted = boxes_.insert(std::make_pair(handles, std::make_pair(node, box))).second; ROS_ASSERT(inserted); + Q_UNUSED(inserted); } else { @@ -260,4 +261,4 @@ InteractiveObjectWPtr SelectionHandler::getInteractiveObject() return interactive_object_; } -} +} // namespace rviz diff --git a/src/rviz/selection/selection_manager.cpp b/src/rviz/selection/selection_manager.cpp index 468f989639..1c2b9aa0b7 100644 --- a/src/rviz/selection/selection_manager.cpp +++ b/src/rviz/selection/selection_manager.cpp @@ -85,9 +85,9 @@ SelectionManager::SelectionManager(VisualizationManager* manager) { for (uint32_t i = 0; i < s_num_render_textures_; ++i) { - pixel_boxes_[i].data = 0; + pixel_boxes_[i].data = nullptr; } - depth_pixel_box_.data = 0; + depth_pixel_box_.data = nullptr; QTimer* timer = new QTimer( this ); connect( timer, SIGNAL( timeout() ), this, SLOT( updateProperties() )); @@ -179,7 +179,7 @@ bool SelectionManager::get3DPoint( Ogre::Viewport* viewport, int x, int y, Ogre: std::vector result_points_temp; bool success = get3DPatch( viewport, x, y, 1, 1, true, result_points_temp); - if (result_points_temp.size() == 0) + if (result_points_temp.empty()) { // return result_point unmodified if get point fails. return false; @@ -309,7 +309,7 @@ bool SelectionManager::get3DPatch( Ogre::Viewport* viewport, int x, int y, unsig ++pixel_counter; } - return result_points.size() > 0; + return !result_points.empty(); } @@ -462,6 +462,7 @@ void SelectionManager::addObject(CollObjectHandle obj, SelectionHandler* handler bool inserted = objects_.insert( std::make_pair( obj, handler )).second; ROS_ASSERT(inserted); + Q_UNUSED(inserted); } void SelectionManager::removeObject(CollObjectHandle obj) @@ -1030,7 +1031,7 @@ Ogre::Technique *SelectionManager::handleSchemeNotFound(unsigned short /*scheme } else { - return NULL; + return nullptr; } } else // Must be CULL_NONE because we never use CULL_ANTICLOCKWISE @@ -1049,7 +1050,7 @@ Ogre::Technique *SelectionManager::handleSchemeNotFound(unsigned short /*scheme } else { - return NULL; + return nullptr; } } } @@ -1090,7 +1091,7 @@ class PickColorSetter: public Ogre::Renderable::Visitor PickColorSetter( CollObjectHandle handle, const Ogre::ColourValue& color ) : color_vector_( color.r, color.g, color.b, 1.0 ), handle_(handle) {} - virtual void visit( Ogre::Renderable* rend, ushort /*lodIndex*/, bool /*isDebug*/, Ogre::Any* /*pAny*/ = 0 ) + void visit( Ogre::Renderable* rend, ushort /*lodIndex*/, bool /*isDebug*/, Ogre::Any* /*pAny*/ = nullptr ) override { rend->setCustomParameter( PICK_COLOR_PARAMETER, color_vector_ ); rend->getUserObjectBindings().setUserAny( "pick_handle", Ogre::Any( handle_ )); @@ -1117,7 +1118,7 @@ SelectionHandler* SelectionManager::getHandler( CollObjectHandle obj ) return it->second; } - return NULL; + return nullptr; } void SelectionManager::removeSelection(const M_Picked& objs) diff --git a/src/rviz/tool_manager.cpp b/src/rviz/tool_manager.cpp index 229d92bdfe..bc23caf252 100644 --- a/src/rviz/tool_manager.cpp +++ b/src/rviz/tool_manager.cpp @@ -52,8 +52,8 @@ ToolManager::ToolManager( DisplayContext* context ) : factory_( new PluginlibFactory( "rviz", "rviz::Tool" )) , property_tree_model_( new PropertyTreeModel( new Property() )) , context_( context ) - , current_tool_( NULL ) - , default_tool_( NULL ) + , current_tool_( nullptr ) + , default_tool_( nullptr ) { connect( property_tree_model_, SIGNAL( configChanged() ), this, SIGNAL( configChanged() )); } @@ -256,7 +256,7 @@ Tool* ToolManager::addTool( const QString& class_id ) // If the default tool is unset and this tool loaded correctly, set // it as the default and current. - if( default_tool_ == NULL && !failed ) + if( default_tool_ == nullptr && !failed ) { setDefaultTool( tool ); setCurrentTool( tool ); @@ -273,8 +273,8 @@ Tool* ToolManager::addTool( const QString& class_id ) void ToolManager::removeTool( int index ) { Tool* tool = tools_.takeAt( index ); - Tool* fallback = NULL; - if( tools_.size() > 0 ) + Tool* fallback = nullptr; + if( !tools_.empty() ) { fallback = tools_[ 0 ]; } diff --git a/src/rviz/view_controller.cpp b/src/rviz/view_controller.cpp index 7c7289616e..cefc0fbe12 100644 --- a/src/rviz/view_controller.cpp +++ b/src/rviz/view_controller.cpp @@ -54,10 +54,10 @@ namespace rviz { ViewController::ViewController() - : context_( NULL ) - , camera_( NULL ) + : context_( nullptr ) + , camera_( nullptr ) , is_active_( false ) - , type_property_( NULL ) + , type_property_( nullptr ) { near_clip_property_ = new FloatProperty( "Near Clip Distance", 0.01f, "Anything closer to the camera than this threshold will not get rendered.", diff --git a/src/rviz/view_manager.cpp b/src/rviz/view_manager.cpp index bfb6ca734f..8f52829411 100644 --- a/src/rviz/view_manager.cpp +++ b/src/rviz/view_manager.cpp @@ -48,8 +48,8 @@ ViewManager::ViewManager( DisplayContext* context ) , root_property_( new ViewControllerContainer ) , property_model_( new PropertyTreeModel( root_property_ )) , factory_( new PluginlibFactory( "rviz", "rviz::ViewController" )) - , current_( NULL ) - , render_panel_( NULL ) + , current_( nullptr ) + , render_panel_( nullptr ) { property_model_->setDragDropClass( "view-controller" ); connect( property_model_, SIGNAL( configChanged() ), this, SIGNAL( configChanged() )); @@ -95,7 +95,7 @@ ViewController* ViewManager::getCurrent() const void ViewManager::setCurrentFrom( ViewController* source_view ) { - if( source_view == NULL ) + if( source_view == nullptr ) { return; } @@ -114,7 +114,7 @@ void ViewManager::onCurrentDestroyed( QObject* obj ) { if( obj == current_ ) { - current_ = NULL; + current_ = nullptr; } } @@ -210,14 +210,14 @@ ViewController* ViewManager::take( ViewController* view ) return qobject_cast( root_property_->takeChildAt( i + 1 )); } } - return NULL; + return nullptr; } ViewController* ViewManager::takeAt( int index ) { if( index < 0 ) { - return NULL; + return nullptr; } return qobject_cast( root_property_->takeChildAt( index + 1 )); } diff --git a/src/rviz/views_panel.cpp b/src/rviz/views_panel.cpp index 0ec2fbdff4..ed2a07acc2 100644 --- a/src/rviz/views_panel.cpp +++ b/src/rviz/views_panel.cpp @@ -47,7 +47,7 @@ namespace rviz ViewsPanel::ViewsPanel( QWidget* parent ) : Panel( parent ) - , view_man_( NULL ) + , view_man_( nullptr ) { camera_type_selector_ = new QComboBox; properties_view_ = new PropertyTreeWidget(); @@ -117,7 +117,7 @@ void ViewsPanel::setViewManager( ViewManager* view_man ) } else { - properties_view_->setModel( NULL ); + properties_view_->setModel( nullptr ); } onCurrentChanged(); } diff --git a/src/rviz/visualization_frame.cpp b/src/rviz/visualization_frame.cpp index a1f3471b6b..475ae68589 100644 --- a/src/rviz/visualization_frame.cpp +++ b/src/rviz/visualization_frame.cpp @@ -111,19 +111,19 @@ namespace rviz VisualizationFrame::VisualizationFrame( QWidget* parent ) : QMainWindow( parent ) - , app_(NULL) - , render_panel_(NULL) - , show_help_action_(NULL) + , app_(nullptr) + , render_panel_(nullptr) + , show_help_action_(nullptr) , preferences_( new Preferences() ) - , file_menu_(NULL) - , recent_configs_menu_(NULL) - , toolbar_(NULL) - , manager_(NULL) - , splash_( NULL ) - , toolbar_actions_( NULL ) + , file_menu_(nullptr) + , recent_configs_menu_(nullptr) + , toolbar_(nullptr) + , manager_(nullptr) + , splash_( nullptr ) + , toolbar_actions_( nullptr ) , show_choose_new_master_option_( false ) - , add_tool_action_( NULL ) - , remove_tool_menu_( NULL ) + , add_tool_action_( nullptr ) + , remove_tool_menu_( nullptr ) , initialized_( false ) , geom_change_detector_( new WidgetGeometryChangeDetector( this )) , loading_( false ) @@ -274,7 +274,7 @@ void VisualizationFrame::initialize(const QString& display_config_file ) if( !ros::isInitialized() ) { int argc = 0; - ros::init( argc, 0, "rviz", ros::init_options::AnonymousName ); + ros::init( argc, nullptr, "rviz", ros::init_options::AnonymousName ); } // Periodically process events for the splash screen. @@ -369,7 +369,7 @@ void VisualizationFrame::initialize(const QString& display_config_file ) if (app_) app_->processEvents(); delete splash_; - splash_ = 0; + splash_ = nullptr; manager_->startUpdate(); initialized_ = true; @@ -614,7 +614,7 @@ void VisualizationFrame::onDockPanelVisibilityChange( bool visible ) void VisualizationFrame::openPreferencesDialog() { - Preferences temp_preferences( *preferences_.get() ); + Preferences temp_preferences( *preferences_ ); PreferencesDialog* dialog = new PreferencesDialog( panel_factory_, &temp_preferences, this ); @@ -679,7 +679,7 @@ void VisualizationFrame::updateRecentConfigMenu() D_string::iterator end = recent_configs_.end(); for (; it != end; ++it) { - if( *it != "" ) + if( !it->empty() ) { std::string display_name = *it; if( display_name == default_display_config_file_ ) @@ -756,7 +756,7 @@ bool VisualizationFrame::loadDisplayConfigHelper(const std::string &full_path) setWindowModified( false ); loading_ = true; - LoadingDialog* dialog = NULL; + LoadingDialog* dialog = nullptr; if( initialized_ ) { dialog = new LoadingDialog( this ); @@ -1266,7 +1266,7 @@ void VisualizationFrame::showHelpPanel() void VisualizationFrame::onHelpDestroyed() { - show_help_action_ = NULL; + show_help_action_ = nullptr; } void VisualizationFrame::onHelpWiki() diff --git a/src/rviz/visualization_manager.cpp b/src/rviz/visualization_manager.cpp index a244fec2ca..43e286a913 100644 --- a/src/rviz/visualization_manager.cpp +++ b/src/rviz/visualization_manager.cpp @@ -93,11 +93,11 @@ class IconizedProperty: public Property { IconizedProperty( const QString& name = QString(), const QVariant default_value = QVariant(), const QString& description = QString(), - Property* parent = 0, - const char *changed_slot = 0, - QObject* receiver = 0 ) + Property* parent = nullptr, + const char *changed_slot = nullptr, + QObject* receiver = nullptr ) :Property( name, default_value, description, parent, changed_slot, receiver ) {}; - virtual QVariant getViewData( int column, int role ) const + QVariant getViewData( int column, int role ) const override { return (column == 0 && role == Qt::DecorationRole) ? icon_ : Property::getViewData(column,role); @@ -133,7 +133,7 @@ VisualizationManager::VisualizationManager( WindowManagerInterface* wm, boost::shared_ptr tf) : ogre_root_( Ogre::Root::getSingletonPtr() ) -, update_timer_(0) +, update_timer_(nullptr) , shutting_down_(false) , render_panel_( render_panel ) , time_update_timer_(0.0f) diff --git a/src/rviz/visualizer_app.cpp b/src/rviz/visualizer_app.cpp index ef36b587bb..6ada4a425d 100644 --- a/src/rviz/visualizer_app.cpp +++ b/src/rviz/visualizer_app.cpp @@ -66,7 +66,7 @@ namespace fs = boost::filesystem; namespace rviz { -bool reloadShaders(std_srvs::Empty::Request&, std_srvs::Empty::Response&) +bool reloadShaders(std_srvs::Empty::Request& /*unused*/, std_srvs::Empty::Response& /*unused*/) { ROS_INFO("Reloading materials."); { @@ -99,9 +99,9 @@ bool reloadShaders(std_srvs::Empty::Request&, std_srvs::Empty::Response&) } VisualizerApp::VisualizerApp() - : app_( 0 ) - , continue_timer_( 0 ) - , frame_( 0 ) + : app_( nullptr ) + , continue_timer_( nullptr ) + , frame_( nullptr ) { } @@ -201,7 +201,7 @@ bool VisualizerApp::init( int argc, char** argv ) frame_ = new VisualizationFrame(); frame_->setApp( this->app_ ); - if( help_path != "" ) + if( !help_path.empty() ) { frame_->setHelpPath( QString::fromStdString( help_path )); } diff --git a/src/test/marker_test.cpp b/src/test/marker_test.cpp index 40e75828d6..9118230f82 100644 --- a/src/test/marker_test.cpp +++ b/src/test/marker_test.cpp @@ -61,7 +61,7 @@ void emitRow(const std::string type_name, uint32_t type, int32_t x_pos, float r, ++count; } -void publishCallback(const ros::TimerEvent&) +void publishCallback(const ros::TimerEvent& /*unused*/) { static uint32_t counter = 0; @@ -687,7 +687,7 @@ void publishCallback(const ros::TimerEvent&) ++counter; } -void frameCallback(const ros::TimerEvent&) +void frameCallback(const ros::TimerEvent& /*unused*/) { static uint32_t counter = 0; diff --git a/src/test/mesh_marker_test.cpp b/src/test/mesh_marker_test.cpp index 1011d53239..6a9060a692 100644 --- a/src/test/mesh_marker_test.cpp +++ b/src/test/mesh_marker_test.cpp @@ -143,7 +143,7 @@ void publishMeshes() } } -void publishCallback(const ros::TimerEvent&) +void publishCallback(const ros::TimerEvent& /*unused*/) { return publishMeshes(); } diff --git a/src/test/new_display_dialog_test.cpp b/src/test/new_display_dialog_test.cpp index 36a6f2f7ba..c1d4ef3dca 100644 --- a/src/test/new_display_dialog_test.cpp +++ b/src/test/new_display_dialog_test.cpp @@ -54,7 +54,7 @@ int main( int argc, char **argv ) empty, &lookup_name, &display_name, - 0 + nullptr ); if( dialog->exec() == QDialog::Accepted ) { diff --git a/src/test/rviz_logo_marker.cpp b/src/test/rviz_logo_marker.cpp index a3c2ceccf5..a3899ef8a3 100644 --- a/src/test/rviz_logo_marker.cpp +++ b/src/test/rviz_logo_marker.cpp @@ -80,7 +80,7 @@ void makeMarker( ) server->applyChanges(); } -void publishCallback(tf::TransformBroadcaster& /*tf_broadcaster*/, const ros::TimerEvent&) +void publishCallback(tf::TransformBroadcaster& /*tf_broadcaster*/, const ros::TimerEvent& /*unused*/) { static tf::TransformBroadcaster br; tf::Transform transform; diff --git a/src/test/uniform_string_stream_test.cpp b/src/test/uniform_string_stream_test.cpp index 6e12ae372c..26aba5ed1b 100644 --- a/src/test/uniform_string_stream_test.cpp +++ b/src/test/uniform_string_stream_test.cpp @@ -67,7 +67,7 @@ TEST( UniformStringStream, parse_ints ) class CommaFloat: public std::numpunct { protected: - virtual char do_decimal_point() const { return 'p'; } + char do_decimal_point() const override { return 'p'; } }; TEST( UniformStringStream, print_floats )