From 5164222f10b7c9a6874758b15e077d0958ec4808 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Fri, 31 Mar 2023 11:01:54 +0200 Subject: [PATCH] Adapt Property creation to use Qt5-style member-function pointers --- src/rviz/default_plugin/axes_display.cpp | 16 +-- src/rviz/default_plugin/camera_display.cpp | 6 +- .../default_plugin/covariance_property.cpp | 30 ++++-- src/rviz/default_plugin/covariance_property.h | 8 +- .../default_plugin/depth_cloud_display.cpp | 24 +++-- src/rviz/default_plugin/effort_display.cpp | 16 +-- .../default_plugin/grid_cells_display.cpp | 2 +- src/rviz/default_plugin/grid_display.cpp | 22 ++-- src/rviz/default_plugin/image_display.cpp | 8 +- .../interactive_marker_display.cpp | 16 +-- src/rviz/default_plugin/map_display.cpp | 17 +-- src/rviz/default_plugin/marker_display.cpp | 4 +- src/rviz/default_plugin/odometry_display.cpp | 20 ++-- src/rviz/default_plugin/path_display.cpp | 27 ++--- .../default_plugin/point_cloud_common.cpp | 16 +-- .../point_cloud_transformers.cpp | 41 +++---- src/rviz/default_plugin/point_display.cpp | 10 +- src/rviz/default_plugin/polygon_display.cpp | 4 +- .../default_plugin/pose_array_display.cpp | 20 ++-- src/rviz/default_plugin/pose_display.cpp | 21 ++-- .../pose_with_covariance_display.cpp | 23 ++-- src/rviz/default_plugin/range_display.cpp | 9 +- .../default_plugin/robot_model_display.cpp | 12 +-- src/rviz/default_plugin/tf_display.cpp | 12 +-- src/rviz/default_plugin/tools/goal_tool.cpp | 2 +- .../tools/initial_pose_tool.cpp | 2 +- .../default_plugin/tools/interaction_tool.cpp | 2 +- src/rviz/default_plugin/tools/point_tool.cpp | 4 +- .../view_controllers/fps_view_controller.cpp | 8 +- .../frame_view_controller.cpp | 2 +- src/rviz/image/image_display_base.cpp | 15 ++- src/rviz/message_filter_display.h | 8 +- src/rviz/robot/robot.cpp | 10 +- src/rviz/robot/robot_joint.cpp | 7 +- src/rviz/robot/robot_link.cpp | 9 +- src/rviz/view_controller.cpp | 17 +-- src/rviz/visualization_frame.cpp | 102 +++++++++++------- src/rviz/visualization_manager.cpp | 13 ++- 38 files changed, 315 insertions(+), 270 deletions(-) diff --git a/src/rviz/default_plugin/axes_display.cpp b/src/rviz/default_plugin/axes_display.cpp index 9854241ef9..ba9e115539 100644 --- a/src/rviz/default_plugin/axes_display.cpp +++ b/src/rviz/default_plugin/axes_display.cpp @@ -47,22 +47,22 @@ AxesDisplay::AxesDisplay() : Display(), axes_(nullptr), trail_(nullptr) { frame_property_ = new TfFrameProperty("Reference Frame", TfFrameProperty::FIXED_FRAME_STRING, "The TF frame these axes will use for their origin.", this, - nullptr, true, SLOT(resetTrail())); + nullptr, true, [this] { resetTrail(); }); - length_property_ = - new FloatProperty("Length", 1.0, "Length of each axis, in meters.", this, SLOT(updateShape())); + length_property_ = new FloatProperty("Length", 1.0, "Length of each axis, in meters.", this, + &AxesDisplay::updateShape); length_property_->setMin(0.0001); - radius_property_ = - new FloatProperty("Radius", 0.1, "Radius of each axis, in meters.", this, SLOT(updateShape())); + radius_property_ = new FloatProperty("Radius", 0.1, "Radius of each axis, in meters.", this, + &AxesDisplay::updateShape); radius_property_->setMin(0.0001); trail_property_ = new Property("Show Trail", false, "Enable/disable a 2 meter \"ribbon\" which follows this frame.", - this, SLOT(updateTrail())); + this, &AxesDisplay::updateTrail); - alpha_property_ = - new FloatProperty("Alpha", 1.0, "Alpha channel value of each axis.", this, SLOT(updateShape())); + alpha_property_ = new FloatProperty("Alpha", 1.0, "Alpha channel value of each axis.", this, + &AxesDisplay::updateShape); alpha_property_->setMin(0.0); alpha_property_->setMax(1.0); } diff --git a/src/rviz/default_plugin/camera_display.cpp b/src/rviz/default_plugin/camera_display.cpp index 39af83e760..28b434ec51 100644 --- a/src/rviz/default_plugin/camera_display.cpp +++ b/src/rviz/default_plugin/camera_display.cpp @@ -84,7 +84,7 @@ CameraDisplay::CameraDisplay() image_position_property_ = new EnumProperty("Image Rendering", BOTH, "Render the image behind all other geometry or overlay it on top, or both.", this, - SLOT(forceRender())); + &CameraDisplay::forceRender); image_position_property_->addOption(BACKGROUND); image_position_property_->addOption(OVERLAY); image_position_property_->addOption(BOTH); @@ -92,14 +92,14 @@ CameraDisplay::CameraDisplay() alpha_property_ = new FloatProperty( "Overlay Alpha", 0.5, "The amount of transparency to apply to the camera image when rendered as overlay.", this, - SLOT(updateAlpha())); + &CameraDisplay::updateAlpha); alpha_property_->setMin(0); alpha_property_->setMax(1); zoom_property_ = new FloatProperty( "Zoom Factor", 1.0, "Set a zoom factor below 1 to see a larger part of the world, above 1 to magnify the image.", this, - SLOT(forceRender())); + &CameraDisplay::forceRender); zoom_property_->setMin(0.00001); zoom_property_->setMax(100000); } diff --git a/src/rviz/default_plugin/covariance_property.cpp b/src/rviz/default_plugin/covariance_property.cpp index 99fac88e57..6329a29c31 100644 --- a/src/rviz/default_plugin/covariance_property.cpp +++ b/src/rviz/default_plugin/covariance_property.cpp @@ -50,16 +50,18 @@ CovarianceProperty::CovarianceProperty(const QString& name, { position_property_ = new BoolProperty("Position", true, "Whether or not to show the position part of covariances", this, - SLOT(updateVisibility())); + qOverload<>(&CovarianceProperty::updateVisibility)); position_property_->setDisableChildrenIfFalse(true); position_color_property_ = new ColorProperty("Color", QColor(204, 51, 204), "Color to draw the position covariance ellipse.", - position_property_, SLOT(updateColorAndAlphaAndScaleAndOffset()), this); + position_property_, + qOverload<>(&CovarianceProperty::updateColorAndAlphaAndScaleAndOffset), this); position_alpha_property_ = new FloatProperty("Alpha", 0.3f, "0 is fully transparent, 1.0 is fully opaque.", - position_property_, SLOT(updateColorAndAlphaAndScaleAndOffset()), this); + position_property_, + qOverload<>(&CovarianceProperty::updateColorAndAlphaAndScaleAndOffset), this); position_alpha_property_->setMin(0); position_alpha_property_->setMax(1); @@ -67,34 +69,38 @@ CovarianceProperty::CovarianceProperty(const QString& name, new FloatProperty("Scale", 1.0f, "Scale factor to be applied to covariance ellipse. " "Corresponds to the number of standard deviations to display", - position_property_, SLOT(updateColorAndAlphaAndScaleAndOffset()), this); + position_property_, + qOverload<>(&CovarianceProperty::updateColorAndAlphaAndScaleAndOffset), this); position_scale_property_->setMin(0); orientation_property_ = new BoolProperty("Orientation", true, "Whether or not to show the orientation part of covariances", - this, SLOT(updateVisibility())); + this, qOverload<>(&CovarianceProperty::updateVisibility)); orientation_property_->setDisableChildrenIfFalse(true); orientation_frame_property_ = new EnumProperty("Frame", "Local", "The frame used to display the orientation covariance.", - orientation_property_, SLOT(updateOrientationFrame()), this); + orientation_property_, qOverload<>(&CovarianceProperty::updateOrientationFrame), + this); orientation_frame_property_->addOption("Local", Local); orientation_frame_property_->addOption("Fixed", Fixed); orientation_colorstyle_property_ = new EnumProperty( "Color Style", "Unique", "Style to color the orientation covariance: XYZ with same unique color or following RGB order", - orientation_property_, SLOT(updateColorStyleChoice()), this); + orientation_property_, &CovarianceProperty::updateColorStyleChoice, this); orientation_colorstyle_property_->addOption("Unique", Unique); orientation_colorstyle_property_->addOption("RGB", RGB); orientation_color_property_ = new ColorProperty("Color", QColor(255, 255, 127), "Color to draw the covariance ellipse.", - orientation_property_, SLOT(updateColorAndAlphaAndScaleAndOffset()), this); + orientation_property_, + qOverload<>(&CovarianceProperty::updateColorAndAlphaAndScaleAndOffset), this); orientation_alpha_property_ = new FloatProperty("Alpha", 0.5f, "0 is fully transparent, 1.0 is fully opaque.", - orientation_property_, SLOT(updateColorAndAlphaAndScaleAndOffset()), this); + orientation_property_, + qOverload<>(&CovarianceProperty::updateColorAndAlphaAndScaleAndOffset), this); orientation_alpha_property_->setMin(0); orientation_alpha_property_->setMax(1); @@ -102,14 +108,16 @@ CovarianceProperty::CovarianceProperty(const QString& name, "Offset", 1.0f, "For 3D poses is the distance where to position the ellipses representing orientation covariance. " "For 2D poses is the height of the triangle representing the variance on yaw.", - orientation_property_, SLOT(updateColorAndAlphaAndScaleAndOffset()), this); + orientation_property_, qOverload<>(&CovarianceProperty::updateColorAndAlphaAndScaleAndOffset), + this); orientation_offset_property_->setMin(0); orientation_scale_property_ = new FloatProperty("Scale", 1.0f, "Scale factor to be applied to orientation covariance shapes. " "Corresponds to the number of standard deviations to display.", - orientation_property_, SLOT(updateColorAndAlphaAndScaleAndOffset()), this); + orientation_property_, + qOverload<>(&CovarianceProperty::updateColorAndAlphaAndScaleAndOffset), this); orientation_scale_property_->setMin(0); connect(this, &Property::changed, this, qOverload<>(&CovarianceProperty::updateVisibility)); diff --git a/src/rviz/default_plugin/covariance_property.h b/src/rviz/default_plugin/covariance_property.h index cbaaca1dae..eae8247116 100644 --- a/src/rviz/default_plugin/covariance_property.h +++ b/src/rviz/default_plugin/covariance_property.h @@ -89,10 +89,10 @@ class CovarianceProperty : public rviz::BoolProperty // this variant is required to allow omitting the receiver argument template CovarianceProperty(const QString& name, - bool default_value, - const QString& description, - P* parent, - Func&& changed_slot) + bool default_value, + const QString& description, + P* parent, + Func&& changed_slot) : CovarianceProperty(name, default_value, description, parent) { connect(parent, std::forward(changed_slot)); diff --git a/src/rviz/default_plugin/depth_cloud_display.cpp b/src/rviz/default_plugin/depth_cloud_display.cpp index f0c1d1a103..7b98d73dcb 100644 --- a/src/rviz/default_plugin/depth_cloud_display.cpp +++ b/src/rviz/default_plugin/depth_cloud_display.cpp @@ -84,15 +84,15 @@ DepthCloudDisplay::DepthCloudDisplay() topic_filter_property_ = new Property("Topic Filter", true, "List only topics with names that relate to depth and color images", this, - SLOT(updateTopicFilter())); + &DepthCloudDisplay::updateTopicFilter); depth_topic_property_ = new RosFilteredTopicProperty( "Depth Map Topic", "", QString::fromStdString(ros::message_traits::datatype()), - "sensor_msgs::Image topic to subscribe to.", depth_filter, this, SLOT(updateTopic())); + "sensor_msgs::Image topic to subscribe to.", depth_filter, this, &DepthCloudDisplay::updateTopic); depth_transport_property_ = new EnumProperty("Depth Map Transport Hint", "raw", "Preferred method of sending images.", this, - SLOT(updateTopic())); + &DepthCloudDisplay::updateTopic); connect(depth_transport_property_, &EnumProperty::requestOptions, this, &DepthCloudDisplay::fillTransportOptionList); @@ -106,10 +106,11 @@ DepthCloudDisplay::DepthCloudDisplay() color_topic_property_ = new RosFilteredTopicProperty( "Color Image Topic", "", QString::fromStdString(ros::message_traits::datatype()), - "sensor_msgs::Image topic to subscribe to.", color_filter, this, SLOT(updateTopic())); + "sensor_msgs::Image topic to subscribe to.", color_filter, this, &DepthCloudDisplay::updateTopic); - color_transport_property_ = new EnumProperty( - "Color Transport Hint", "raw", "Preferred method of sending images.", this, SLOT(updateTopic())); + color_transport_property_ = + new EnumProperty("Color Transport Hint", "raw", "Preferred method of sending images.", this, + &DepthCloudDisplay::updateTopic); connect(color_transport_property_, &EnumProperty::requestOptions, this, @@ -123,29 +124,30 @@ DepthCloudDisplay::DepthCloudDisplay() "Advanced: set the size of the incoming message queue. Increasing this " "is useful if your incoming TF data is delayed significantly from your" " image data, but it can greatly increase memory usage if the messages are big.", - this, SLOT(updateQueueSize())); + this, &DepthCloudDisplay::updateQueueSize); queue_size_property_->setMin(1); use_auto_size_property_ = new BoolProperty( "Auto Size", true, "Automatically scale each point based on its depth value and the camera parameters.", this, - SLOT(updateUseAutoSize()), this); + &DepthCloudDisplay::updateUseAutoSize, this); auto_size_factor_property_ = new FloatProperty("Auto Size Factor", 1, "Scaling factor to be applied to the auto size.", - use_auto_size_property_, SLOT(updateAutoSizeFactor()), this); + use_auto_size_property_, &DepthCloudDisplay::updateAutoSizeFactor, this); auto_size_factor_property_->setMin(0.0001); use_occlusion_compensation_property_ = new BoolProperty("Occlusion Compensation", false, "Keep points alive after they have been occluded by a closer point. Points are " "removed after a timeout or when the camera frame moves.", - this, SLOT(updateUseOcclusionCompensation()), this); + this, &DepthCloudDisplay::updateUseOcclusionCompensation, this); occlusion_shadow_timeout_property_ = new FloatProperty("Occlusion Time-Out", 30.0f, "Amount of seconds before removing occluded points from the depth cloud", - use_occlusion_compensation_property_, SLOT(updateOcclusionTimeOut()), this); + use_occlusion_compensation_property_, &DepthCloudDisplay::updateOcclusionTimeOut, + this); } void DepthCloudDisplay::onInitialize() diff --git a/src/rviz/default_plugin/effort_display.cpp b/src/rviz/default_plugin/effort_display.cpp index ce9bd549c7..51ef115bf4 100644 --- a/src/rviz/default_plugin/effort_display.cpp +++ b/src/rviz/default_plugin/effort_display.cpp @@ -26,7 +26,7 @@ JointInfo::JointInfo(const std::string& name, rviz::Property* parent_category) // info->category_ = new Property( QString::fromStdString( info->name_ ) , QVariant(), "", // joints_category_); category_ = new rviz::Property(QString::fromStdString(name_), true, "", parent_category, - SLOT(updateVisibility()), this); + &JointInfo::updateVisibility, this); effort_property_ = new rviz::FloatProperty("Effort", 0, "Effort value of this joint.", category_); effort_property_->setReadOnly(true); @@ -81,17 +81,17 @@ JointInfo* EffortDisplay::createJoint(const std::string& joint) EffortDisplay::EffortDisplay() { alpha_property_ = new rviz::FloatProperty("Alpha", 1.0, "0 is fully transparent, 1.0 is fully opaque.", - this, SLOT(updateColorAndAlpha())); + this, &EffortDisplay::updateColorAndAlpha); width_property_ = new rviz::FloatProperty("Width", 0.02, "Width to drow effort circle", this, - SLOT(updateColorAndAlpha())); + &EffortDisplay::updateColorAndAlpha); scale_property_ = new rviz::FloatProperty("Scale", 1.0, "Scale to drow effort circle", this, - SLOT(updateColorAndAlpha())); + &EffortDisplay::updateColorAndAlpha); history_length_property_ = new rviz::IntProperty("History Length", 1, "Number of prior measurements to display.", this, - SLOT(updateHistoryLength())); + &EffortDisplay::updateHistoryLength); history_length_property_->setMin(1); history_length_property_->setMax(100000); @@ -99,13 +99,13 @@ EffortDisplay::EffortDisplay() new rviz::StringProperty("Robot Description", "robot_description", "Name of the parameter to search for to load the robot " "description.", - this, SLOT(updateRobotDescription())); + this, &EffortDisplay::updateRobotDescription); tf_prefix_property_ = new StringProperty( "TF Prefix", "", "Robot Model normally assumes the link name is the same as the tf frame name. " "This option allows you to set a prefix. Mainly useful for multi-robot situations.", - this, SLOT(updateTfPrefix())); + this, &EffortDisplay::updateTfPrefix); joints_category_ = new rviz::Property("Joints", QVariant(), "", this); } @@ -192,7 +192,7 @@ void EffortDisplay::load() QString("Parameter [%1] does not exist, and was not found by searchParam()") .arg(robot_description_property_->getString())); // try again in a second - QTimer::singleShot(1000, this, SLOT(updateRobotDescription())); + QTimer::singleShot(1000, this, &EffortDisplay::updateRobotDescription); return; } } diff --git a/src/rviz/default_plugin/grid_cells_display.cpp b/src/rviz/default_plugin/grid_cells_display.cpp index c1e6b7dbc0..79e19e836f 100644 --- a/src/rviz/default_plugin/grid_cells_display.cpp +++ b/src/rviz/default_plugin/grid_cells_display.cpp @@ -50,7 +50,7 @@ GridCellsDisplay::GridCellsDisplay() : MFDClass(), last_frame_count_(uint64_t(-1 color_property_ = new ColorProperty("Color", QColor(25, 255, 0), "Color of the grid cells.", this); alpha_property_ = new FloatProperty("Alpha", 1.0, "Amount of transparency to apply to the cells.", - this, SLOT(updateAlpha())); + this, &GridCellsDisplay::updateAlpha); alpha_property_->setMin(0); alpha_property_->setMax(1); } diff --git a/src/rviz/default_plugin/grid_display.cpp b/src/rviz/default_plugin/grid_display.cpp index a2154bed76..ba8ecc1605 100644 --- a/src/rviz/default_plugin/grid_display.cpp +++ b/src/rviz/default_plugin/grid_display.cpp @@ -53,42 +53,42 @@ GridDisplay::GridDisplay() : Display() cell_count_property_ = new IntProperty("Plane Cell Count", 10, "The number of cells to draw in the plane of the grid.", - this, SLOT(updateCellCount())); + this, &GridDisplay::updateCellCount); cell_count_property_->setMin(1); height_property_ = new IntProperty("Normal Cell Count", 0, "The number of cells to draw along the normal vector of the grid. " " Setting to anything but 0 makes the grid 3D.", - this, SLOT(updateHeight())); + this, &GridDisplay::updateHeight); height_property_->setMin(0); cell_size_property_ = new FloatProperty("Cell Size", 1.0f, "The length, in meters, of the side of each cell.", this, - SLOT(updateCellSize())); + &GridDisplay::updateCellSize); cell_size_property_->setMin(0.0001); style_property_ = new EnumProperty("Line Style", "Lines", "The rendering operation to use to draw the grid lines.", - this, SLOT(updateStyle())); + this, &GridDisplay::updateStyle); style_property_->addOption("Lines", Grid::Lines); style_property_->addOption("Billboards", Grid::Billboards); line_width_property_ = new FloatProperty("Line Width", 0.03, "The width, in meters, of each grid line.", style_property_, - SLOT(updateLineWidth()), this); + &GridDisplay::updateLineWidth, this); line_width_property_->setMin(0.001); line_width_property_->hide(); - color_property_ = - new ColorProperty("Color", Qt::gray, "The color of the grid lines.", this, SLOT(updateColor())); + color_property_ = new ColorProperty("Color", Qt::gray, "The color of the grid lines.", this, + &GridDisplay::updateColor); alpha_property_ = new FloatProperty("Alpha", 0.5f, "The amount of transparency to apply to the grid lines.", this, - SLOT(updateColor())); + &GridDisplay::updateColor); alpha_property_->setMin(0.0f); alpha_property_->setMax(1.0f); - plane_property_ = - new EnumProperty("Plane", "XY", "The plane to draw the grid along.", this, SLOT(updatePlane())); + plane_property_ = new EnumProperty("Plane", "XY", "The plane to draw the grid along.", this, + &GridDisplay::updatePlane); plane_property_->addOption("XY", XY); plane_property_->addOption("XZ", XZ); plane_property_->addOption("YZ", YZ); @@ -96,7 +96,7 @@ GridDisplay::GridDisplay() : Display() offset_property_ = new VectorProperty( "Offset", Ogre::Vector3::ZERO, "Allows you to offset the grid from the origin of the reference frame. In meters.", this, - SLOT(updateOffset())); + &GridDisplay::updateOffset); } GridDisplay::~GridDisplay() diff --git a/src/rviz/default_plugin/image_display.cpp b/src/rviz/default_plugin/image_display.cpp index 647283d380..91847beddd 100644 --- a/src/rviz/default_plugin/image_display.cpp +++ b/src/rviz/default_plugin/image_display.cpp @@ -59,17 +59,17 @@ ImageDisplay::ImageDisplay() : ImageDisplayBase(), texture_() normalize_property_ = new BoolProperty( "Normalize Range", true, "If set to true, will try to estimate the range of possible values from the received images.", - this, SLOT(updateNormalizeOptions())); + this, &ImageDisplay::updateNormalizeOptions); min_property_ = new FloatProperty("Min Value", 0.0, "Value which will be displayed as black.", this, - SLOT(updateNormalizeOptions())); + &ImageDisplay::updateNormalizeOptions); max_property_ = new FloatProperty("Max Value", 1.0, "Value which will be displayed as white.", this, - SLOT(updateNormalizeOptions())); + &ImageDisplay::updateNormalizeOptions); median_buffer_size_property_ = new IntProperty("Median window", 5, "Window size for median filter used for computin min/max.", - this, SLOT(updateNormalizeOptions())); + this, &ImageDisplay::updateNormalizeOptions); got_float_image_ = false; } diff --git a/src/rviz/default_plugin/interactive_marker_display.cpp b/src/rviz/default_plugin/interactive_marker_display.cpp index bae8f6c330..0a1bf63582 100644 --- a/src/rviz/default_plugin/interactive_marker_display.cpp +++ b/src/rviz/default_plugin/interactive_marker_display.cpp @@ -81,27 +81,29 @@ bool validateQuaternions(const visualization_msgs::InteractiveMarker& marker) InteractiveMarkerDisplay::InteractiveMarkerDisplay() : Display() { - marker_update_topic_property_ = new RosTopicProperty( - "Update Topic", "", ros::message_traits::datatype(), - "visualization_msgs::InteractiveMarkerUpdate topic to subscribe to.", this, SLOT(updateTopic())); + marker_update_topic_property_ = + new RosTopicProperty("Update Topic", "", + ros::message_traits::datatype(), + "visualization_msgs::InteractiveMarkerUpdate topic to subscribe to.", this, + &InteractiveMarkerDisplay::updateTopic); show_descriptions_property_ = new BoolProperty("Show Descriptions", true, "Whether or not to show the descriptions of each Interactive Marker.", this, - SLOT(updateShowDescriptions())); + &InteractiveMarkerDisplay::updateShowDescriptions); show_axes_property_ = new BoolProperty("Show Axes", false, "Whether or not to show the axes of each Interactive Marker.", - this, SLOT(updateShowAxes())); + this, &InteractiveMarkerDisplay::updateShowAxes); show_visual_aids_property_ = new BoolProperty( "Show Visual Aids", false, "Whether or not to show visual helpers while moving/rotating Interactive Markers.", this, - SLOT(updateShowVisualAids())); + &InteractiveMarkerDisplay::updateShowVisualAids); enable_transparency_property_ = new BoolProperty( "Enable Transparency", true, "Whether or not to allow transparency for auto-completed markers (e.g. rings and arrows).", this, - SLOT(updateEnableTransparency())); + &InteractiveMarkerDisplay::updateEnableTransparency); } void InteractiveMarkerDisplay::onInitialize() diff --git a/src/rviz/default_plugin/map_display.cpp b/src/rviz/default_plugin/map_display.cpp index 8a034e3a1d..a106c8da4f 100644 --- a/src/rviz/default_plugin/map_display.cpp +++ b/src/rviz/default_plugin/map_display.cpp @@ -224,15 +224,15 @@ MapDisplay::MapDisplay() : Display(), loaded_(false), resolution_(0.0f), width_( connect(this, &MapDisplay::mapUpdated, this, &MapDisplay::showMap); topic_property_ = new RosTopicProperty( "Topic", "", QString::fromStdString(ros::message_traits::datatype()), - "nav_msgs::OccupancyGrid topic to subscribe to.", this, SLOT(updateTopic())); + "nav_msgs::OccupancyGrid topic to subscribe to.", this, &MapDisplay::updateTopic); alpha_property_ = new FloatProperty("Alpha", 0.7, "Amount of transparency to apply to the map.", this, - SLOT(updateAlpha())); + &MapDisplay::updateAlpha); alpha_property_->setMin(0); alpha_property_->setMax(1); color_scheme_property_ = new EnumProperty("Color Scheme", "map", "How to color the occupancy values.", - this, SLOT(updatePalette())); + this, &MapDisplay::updatePalette); // Option values here must correspond to indices in palette_textures_ array in onInitialize() below. color_scheme_property_->addOption("map", 0); color_scheme_property_->addOption("costmap", 1); @@ -241,7 +241,7 @@ MapDisplay::MapDisplay() : Display(), loaded_(false), resolution_(0.0f), width_( draw_under_property_ = new Property( "Draw Behind", false, "Rendering option, controls whether or not the map is always drawn behind everything else.", this, - SLOT(updateDrawUnder())); + &MapDisplay::updateDrawUnder); resolution_property_ = new FloatProperty("Resolution", 0, "Resolution of the map. (not editable)", this); @@ -263,11 +263,12 @@ MapDisplay::MapDisplay() : Display(), loaded_(false), resolution_(0.0f), width_( "Orientation of the map. (not editable)", this); orientation_property_->setReadOnly(true); - unreliable_property_ = - new BoolProperty("Unreliable", false, "Prefer UDP topic transport", this, SLOT(updateTopic())); + unreliable_property_ = new BoolProperty("Unreliable", false, "Prefer UDP topic transport", this, + &MapDisplay::updateTopic); - transform_timestamp_property_ = new BoolProperty( - "Use Timestamp", false, "Use map header timestamp when transforming", this, SLOT(transformMap())); + transform_timestamp_property_ = + new BoolProperty("Use Timestamp", false, "Use map header timestamp when transforming", this, + &MapDisplay::transformMap); } MapDisplay::~MapDisplay() diff --git a/src/rviz/default_plugin/marker_display.cpp b/src/rviz/default_plugin/marker_display.cpp index 327e5ab6b9..d26c9686ed 100644 --- a/src/rviz/default_plugin/marker_display.cpp +++ b/src/rviz/default_plugin/marker_display.cpp @@ -56,14 +56,14 @@ MarkerDisplay::MarkerDisplay() : Display(), tf_filter_(nullptr) QString::fromStdString(ros::message_traits::datatype()), "visualization_msgs::Marker topic to subscribe to. _array will also" " automatically be subscribed with type visualization_msgs::MarkerArray.", - this, SLOT(updateTopic())); + this, &MarkerDisplay::updateTopic); queue_size_property_ = new IntProperty("Queue Size", 100, "Advanced: set the size of the incoming Marker message queue. Increasing this is" " useful if your incoming TF data is delayed significantly from your Marker data, " "but it can greatly increase memory usage if the messages are big.", - this, SLOT(updateQueueSize())); + this, &MarkerDisplay::updateQueueSize); queue_size_property_->setMin(0); namespaces_category_ = new Property("Namespaces", QVariant(), "", this); diff --git a/src/rviz/default_plugin/odometry_display.cpp b/src/rviz/default_plugin/odometry_display.cpp index c9181055e6..44c6208a51 100644 --- a/src/rviz/default_plugin/odometry_display.cpp +++ b/src/rviz/default_plugin/odometry_display.cpp @@ -66,46 +66,46 @@ OdometryDisplay::OdometryDisplay() keep_property_->setMin(0); shape_property_ = new EnumProperty("Shape", "Arrow", "Shape to display the pose as.", this, - SLOT(updateShapeChoice())); + &OdometryDisplay::updateShapeChoice); shape_property_->addOption("Arrow", ArrowShape); shape_property_->addOption("Axes", AxesShape); color_property_ = new ColorProperty("Color", QColor(255, 25, 0), "Color of the arrows.", - shape_property_, SLOT(updateColorAndAlpha()), this); + shape_property_, &OdometryDisplay::updateColorAndAlpha, this); alpha_property_ = new FloatProperty("Alpha", 1, "Amount of transparency to apply to the arrow.", - shape_property_, SLOT(updateColorAndAlpha()), this); + shape_property_, &OdometryDisplay::updateColorAndAlpha, this); alpha_property_->setMin(0); alpha_property_->setMax(1); shaft_length_property_ = new FloatProperty("Shaft Length", 1, "Length of the each arrow's shaft, in meters.", - shape_property_, SLOT(updateArrowsGeometry()), this); + shape_property_, &OdometryDisplay::updateArrowsGeometry, this); // aleeper: default changed from 0.1 to match change in arrow.cpp shaft_radius_property_ = new FloatProperty("Shaft Radius", 0.05, "Radius of the each arrow's shaft, in meters.", - shape_property_, SLOT(updateArrowsGeometry()), this); + shape_property_, &OdometryDisplay::updateArrowsGeometry, this); head_length_property_ = new FloatProperty("Head Length", 0.3, "Length of the each arrow's head, in meters.", - shape_property_, SLOT(updateArrowsGeometry()), this); + shape_property_, &OdometryDisplay::updateArrowsGeometry, this); // aleeper: default changed from 0.2 to match change in arrow.cpp head_radius_property_ = new FloatProperty("Head Radius", 0.1, "Radius of the each arrow's head, in meters.", - shape_property_, SLOT(updateArrowsGeometry()), this); + shape_property_, &OdometryDisplay::updateArrowsGeometry, this); axes_length_property_ = new FloatProperty("Axes Length", 1, "Length of each axis, in meters.", - shape_property_, SLOT(updateAxisGeometry()), this); + shape_property_, &OdometryDisplay::updateAxisGeometry, this); axes_radius_property_ = new FloatProperty("Axes Radius", 0.1, "Radius of each axis, in meters.", - shape_property_, SLOT(updateAxisGeometry()), this); + shape_property_, &OdometryDisplay::updateAxisGeometry, this); covariance_property_ = new CovarianceProperty("Covariance", true, "Whether or not the covariances of the messages should be shown.", this, - SLOT(queueRender())); + &OdometryDisplay::queueRender); } OdometryDisplay::~OdometryDisplay() diff --git a/src/rviz/default_plugin/path_display.cpp b/src/rviz/default_plugin/path_display.cpp index adc773d68c..7e2565f91b 100644 --- a/src/rviz/default_plugin/path_display.cpp +++ b/src/rviz/default_plugin/path_display.cpp @@ -53,7 +53,7 @@ PathDisplay::PathDisplay() { style_property_ = new EnumProperty("Line Style", "Lines", "The rendering operation to use to draw the grid lines.", - this, SLOT(updateStyle())); + this, &PathDisplay::updateStyle); style_property_->addOption("Lines", LINES); style_property_->addOption("Billboards", BILLBOARDS); @@ -61,7 +61,7 @@ PathDisplay::PathDisplay() line_width_property_ = new FloatProperty( "Line Width", 0.03, "The width, in meters, of each path line. Only works with the 'Billboards' style.", this, - SLOT(updateLineWidth()), this); + &PathDisplay::updateLineWidth, this); line_width_property_->setMin(0.001); line_width_property_->hide(); @@ -71,36 +71,37 @@ PathDisplay::PathDisplay() new FloatProperty("Alpha", 1.0, "Amount of transparency to apply to the path.", this); buffer_length_property_ = new IntProperty("Buffer Length", 1, "Number of paths to display.", this, - SLOT(updateBufferLength())); + &PathDisplay::updateBufferLength); buffer_length_property_->setMin(1); offset_property_ = new VectorProperty( "Offset", Ogre::Vector3::ZERO, "Allows you to offset the path from the origin of the reference frame. In meters.", this, - SLOT(updateOffset())); + &PathDisplay::updateOffset); pose_style_property_ = new EnumProperty("Pose Style", "None", "Shape to display the pose as.", this, - SLOT(updatePoseStyle())); + &PathDisplay::updatePoseStyle); pose_style_property_->addOption("None", NONE); pose_style_property_->addOption("Axes", AXES); pose_style_property_->addOption("Arrows", ARROWS); pose_axes_length_property_ = new rviz::FloatProperty("Length", 0.3, "Length of the axes.", this, - SLOT(updatePoseAxisGeometry())); + &PathDisplay::updatePoseAxisGeometry); pose_axes_radius_property_ = new rviz::FloatProperty("Radius", 0.03, "Radius of the axes.", this, - SLOT(updatePoseAxisGeometry())); + &PathDisplay::updatePoseAxisGeometry); pose_arrow_color_property_ = new ColorProperty("Pose Color", QColor(255, 85, 255), "Color to draw the poses.", this, - SLOT(updatePoseArrowColor())); + &PathDisplay::updatePoseArrowColor); pose_arrow_shaft_length_property_ = new rviz::FloatProperty( - "Shaft Length", 0.1, "Length of the arrow shaft.", this, SLOT(updatePoseArrowGeometry())); + "Shaft Length", 0.1, "Length of the arrow shaft.", this, &PathDisplay::updatePoseArrowGeometry); pose_arrow_head_length_property_ = new rviz::FloatProperty( - "Head Length", 0.2, "Length of the arrow head.", this, SLOT(updatePoseArrowGeometry())); - pose_arrow_shaft_diameter_property_ = new rviz::FloatProperty( - "Shaft Diameter", 0.1, "Diameter of the arrow shaft.", this, SLOT(updatePoseArrowGeometry())); + "Head Length", 0.2, "Length of the arrow head.", this, &PathDisplay::updatePoseArrowGeometry); + pose_arrow_shaft_diameter_property_ = + new rviz::FloatProperty("Shaft Diameter", 0.1, "Diameter of the arrow shaft.", this, + &PathDisplay::updatePoseArrowGeometry); pose_arrow_head_diameter_property_ = new rviz::FloatProperty( - "Head Diameter", 0.3, "Diameter of the arrow head.", this, SLOT(updatePoseArrowGeometry())); + "Head Diameter", 0.3, "Diameter of the arrow head.", this, &PathDisplay::updatePoseArrowGeometry); pose_axes_length_property_->hide(); pose_axes_radius_property_->hide(); pose_arrow_color_property_->hide(); diff --git a/src/rviz/default_plugin/point_cloud_common.cpp b/src/rviz/default_plugin/point_cloud_common.cpp index df6bfb909e..6f4a1c9eb1 100644 --- a/src/rviz/default_plugin/point_cloud_common.cpp +++ b/src/rviz/default_plugin/point_cloud_common.cpp @@ -316,11 +316,11 @@ PointCloudCommon::PointCloudCommon(Display* display) selectable_property_ = new BoolProperty("Selectable", true, "Whether or not the points in this point cloud are selectable.", display_, - SLOT(updateSelectable()), this); + &PointCloudCommon::updateSelectable, this); style_property_ = new EnumProperty("Style", "Flat Squares", "Rendering mode to use, in order of computational complexity.", - display_, SLOT(updateStyle()), this); + display_, &PointCloudCommon::updateStyle, this); style_property_->addOption("Points", PointCloud::RM_POINTS); style_property_->addOption("Squares", PointCloud::RM_SQUARES); style_property_->addOption("Flat Squares", PointCloud::RM_FLAT_SQUARES); @@ -328,37 +328,37 @@ PointCloudCommon::PointCloudCommon(Display* display) style_property_->addOption("Boxes", PointCloud::RM_BOXES); point_world_size_property_ = new FloatProperty("Size (m)", 0.01, "Point size in meters.", display_, - SLOT(updateBillboardSize()), this); + &PointCloudCommon::updateBillboardSize, this); point_world_size_property_->setMin(0.0001); point_pixel_size_property_ = new FloatProperty("Size (Pixels)", 3, "Point size in pixels.", display_, - SLOT(updateBillboardSize()), this); + &PointCloudCommon::updateBillboardSize, this); point_pixel_size_property_->setMin(1); alpha_property_ = new FloatProperty("Alpha", 1.0, "Amount of transparency to apply to the points. " "Note that this is experimental and does not always look correct.", - display_, SLOT(updateAlpha()), this); + display_, &PointCloudCommon::updateAlpha, this); alpha_property_->setMin(0); alpha_property_->setMax(1); decay_time_property_ = new FloatProperty( "Decay Time", 0, "Duration, in seconds, to keep the incoming points. 0 means only show the latest points.", - display_, SLOT(queueRender())); + display_, &Display::queueRender); decay_time_property_->setMin(0); xyz_transformer_property_ = new EnumProperty("Position Transformer", "", "Set the transformer to use to set the position of the points.", display_, - SLOT(updateXyzTransformer()), this); + &PointCloudCommon::updateXyzTransformer, this); connect(xyz_transformer_property_, &EnumProperty::requestOptions, this, &PointCloudCommon::setXyzTransformerOptions); color_transformer_property_ = new EnumProperty("Color Transformer", "", "Set the transformer to use to set the color of the points.", display_, - SLOT(updateColorTransformer()), this); + &PointCloudCommon::updateColorTransformer, this); connect(color_transformer_property_, &EnumProperty::requestOptions, this, &PointCloudCommon::setColorTransformerOptions); } diff --git a/src/rviz/default_plugin/point_cloud_transformers.cpp b/src/rviz/default_plugin/point_cloud_transformers.cpp index bf3fcafbaa..3af7b6f411 100644 --- a/src/rviz/default_plugin/point_cloud_transformers.cpp +++ b/src/rviz/default_plugin/point_cloud_transformers.cpp @@ -186,30 +186,35 @@ void IntensityPCTransformer::createProperties(Property* parent_property, channel_name_property_ = new EditableEnumProperty("Channel Name", "intensity", "Select the channel to use to compute the intensity", parent_property, - SIGNAL(needRetransform()), this); + &IntensityPCTransformer::needRetransform, this); use_rainbow_property_ = new BoolProperty("Use rainbow", true, "Whether to use a rainbow of colors or interpolate between two", - parent_property, SLOT(updateUseRainbow()), this); + parent_property, &IntensityPCTransformer::updateUseRainbow, this); invert_rainbow_property_ = new BoolProperty("Invert Rainbow", false, "Whether to invert rainbow colors", parent_property, - SLOT(updateUseRainbow()), this); - - min_color_property_ = new ColorProperty("Min Color", Qt::black, - "Color to assign the points with the minimum intensity. " - "Actual color is interpolated between this and Max Color.", - parent_property, SIGNAL(needRetransform()), this); - - max_color_property_ = new ColorProperty("Max Color", Qt::white, - "Color to assign the points with the maximum intensity. " - "Actual color is interpolated between this and Min Color.", - parent_property, SIGNAL(needRetransform()), this); + &IntensityPCTransformer::updateUseRainbow, this); + + min_color_property_ = + new ColorProperty("Min Color", Qt::black, + "Color to assign the points with the minimum intensity. " + "Actual color is interpolated between this and Max Color.", + parent_property, + &IntensityPCTransformer::IntensityPCTransformer::needRetransform, this); + + max_color_property_ = + new ColorProperty("Max Color", Qt::white, + "Color to assign the points with the maximum intensity. " + "Actual color is interpolated between this and Min Color.", + parent_property, + &IntensityPCTransformer::IntensityPCTransformer::needRetransform, this); auto_compute_intensity_bounds_property_ = new BoolProperty("Autocompute Intensity Bounds", true, "Whether to automatically compute the intensity min/max values.", - parent_property, SLOT(updateAutoComputeIntensityBounds()), this); + parent_property, &IntensityPCTransformer::updateAutoComputeIntensityBounds, + this); min_intensity_property_ = new FloatProperty( "Min Intensity", 0, @@ -553,7 +558,7 @@ void FlatColorPCTransformer::createProperties(Property* parent_property, if (mask & Support_Color) { color_property_ = new ColorProperty("Color", Qt::white, "Color to assign to every point.", - parent_property, SIGNAL(needRetransform()), this); + parent_property, &IntensityPCTransformer::needRetransform, this); out_props.push_back(color_property_); } } @@ -658,7 +663,7 @@ void AxisColorPCTransformer::createProperties(Property* parent_property, if (mask & Support_Color) { axis_property_ = new EnumProperty("Axis", "Z", "The axis to interpolate the color along.", - parent_property, SIGNAL(needRetransform()), this); + parent_property, &IntensityPCTransformer::needRetransform, this); axis_property_->addOption("X", AXIS_X); axis_property_->addOption("Y", AXIS_Y); axis_property_->addOption("Z", AXIS_Z); @@ -666,7 +671,7 @@ void AxisColorPCTransformer::createProperties(Property* parent_property, auto_compute_bounds_property_ = new BoolProperty("Autocompute Value Bounds", true, "Whether to automatically compute the value min/max values.", parent_property, - SLOT(updateAutoComputeBounds()), this); + &AxisColorPCTransformer::updateAutoComputeBounds, this); min_value_property_ = new FloatProperty("Min Value", -10, @@ -681,7 +686,7 @@ void AxisColorPCTransformer::createProperties(Property* parent_property, use_fixed_frame_property_ = new BoolProperty( "Use Fixed Frame", true, "Whether to color the cloud based on its fixed frame position or its local frame position.", - parent_property, SIGNAL(needRetransform()), this); + parent_property, &IntensityPCTransformer::needRetransform, this); out_props.push_back(axis_property_); out_props.push_back(auto_compute_bounds_property_); diff --git a/src/rviz/default_plugin/point_display.cpp b/src/rviz/default_plugin/point_display.cpp index 6a1e6062f3..a9857d11f0 100644 --- a/src/rviz/default_plugin/point_display.cpp +++ b/src/rviz/default_plugin/point_display.cpp @@ -17,17 +17,17 @@ namespace rviz PointStampedDisplay::PointStampedDisplay() { color_property_ = new rviz::ColorProperty("Color", QColor(204, 41, 204), "Color of a point", this, - SLOT(updateColorAndAlpha())); + &PointStampedDisplay::updateColorAndAlpha); alpha_property_ = new rviz::FloatProperty("Alpha", 1.0, "0 is fully transparent, 1.0 is fully opaque.", - this, SLOT(updateColorAndAlpha())); + this, &PointStampedDisplay::updateColorAndAlpha); - radius_property_ = - new rviz::FloatProperty("Radius", 0.2, "Radius of a point", this, SLOT(updateColorAndAlpha())); + radius_property_ = new rviz::FloatProperty("Radius", 0.2, "Radius of a point", this, + &PointStampedDisplay::updateColorAndAlpha); history_length_property_ = new rviz::IntProperty("History Length", 1, "Number of prior measurements to display.", this, - SLOT(updateHistoryLength())); + &PointStampedDisplay::updateHistoryLength); history_length_property_->setMin(1); history_length_property_->setMax(100000); } diff --git a/src/rviz/default_plugin/polygon_display.cpp b/src/rviz/default_plugin/polygon_display.cpp index c4494c3ff3..15b4d84b4e 100644 --- a/src/rviz/default_plugin/polygon_display.cpp +++ b/src/rviz/default_plugin/polygon_display.cpp @@ -45,9 +45,9 @@ namespace rviz PolygonDisplay::PolygonDisplay() { color_property_ = new ColorProperty("Color", QColor(25, 255, 0), "Color to draw the polygon.", this, - SLOT(queueRender())); + &PolygonDisplay::queueRender); alpha_property_ = new FloatProperty("Alpha", 1.0, "Amount of transparency to apply to the polygon.", - this, SLOT(queueRender())); + this, &PolygonDisplay::queueRender); alpha_property_->setMin(0); alpha_property_->setMax(1); } diff --git a/src/rviz/default_plugin/pose_array_display.cpp b/src/rviz/default_plugin/pose_array_display.cpp index 270e3bb425..70376b83b6 100644 --- a/src/rviz/default_plugin/pose_array_display.cpp +++ b/src/rviz/default_plugin/pose_array_display.cpp @@ -73,39 +73,39 @@ Ogre::Quaternion quaternionRosToOgre(geometry_msgs::Quaternion const& quaternion PoseArrayDisplay::PoseArrayDisplay() : manual_object_(nullptr) { shape_property_ = new EnumProperty("Shape", "Arrow (Flat)", "Shape to display the pose as.", this, - SLOT(updateShapeChoice())); + &PoseArrayDisplay::updateShapeChoice); arrow_color_property_ = new ColorProperty("Color", QColor(255, 25, 0), "Color to draw the arrows.", - this, SLOT(updateArrowColor())); + this, &PoseArrayDisplay::updateArrowColor); arrow_alpha_property_ = new FloatProperty("Alpha", 1, "Amount of transparency to apply to the displayed poses.", this, - SLOT(updateArrowColor())); + &PoseArrayDisplay::updateArrowColor); arrow2d_length_property_ = new FloatProperty("Arrow Length", 0.3, "Length of the arrows.", this, - SLOT(updateArrow2dGeometry())); + &PoseArrayDisplay::updateArrow2dGeometry); arrow3d_head_radius_property_ = new FloatProperty("Head Radius", 0.03, "Radius of the arrow's head, in meters.", this, - SLOT(updateArrow3dGeometry())); + &PoseArrayDisplay::updateArrow3dGeometry); arrow3d_head_length_property_ = new FloatProperty("Head Length", 0.07, "Length of the arrow's head, in meters.", this, - SLOT(updateArrow3dGeometry())); + &PoseArrayDisplay::updateArrow3dGeometry); arrow3d_shaft_radius_property_ = new FloatProperty("Shaft Radius", 0.01, "Radius of the arrow's shaft, in meters.", this, - SLOT(updateArrow3dGeometry())); + &PoseArrayDisplay::updateArrow3dGeometry); arrow3d_shaft_length_property_ = new FloatProperty("Shaft Length", 0.23, "Length of the arrow's shaft, in meters.", this, - SLOT(updateArrow3dGeometry())); + &PoseArrayDisplay::updateArrow3dGeometry); axes_length_property_ = new FloatProperty("Axes Length", 0.3, "Length of each axis, in meters.", this, - SLOT(updateAxesGeometry())); + &PoseArrayDisplay::updateAxesGeometry); axes_radius_property_ = new FloatProperty("Axes Radius", 0.01, "Radius of each axis, in meters.", this, - SLOT(updateAxesGeometry())); + &PoseArrayDisplay::updateAxesGeometry); shape_property_->addOption("Arrow (Flat)", ShapeType::Arrow2d); shape_property_->addOption("Arrow (3D)", ShapeType::Arrow3d); diff --git a/src/rviz/default_plugin/pose_display.cpp b/src/rviz/default_plugin/pose_display.cpp index 42d201326c..7dfc084545 100644 --- a/src/rviz/default_plugin/pose_display.cpp +++ b/src/rviz/default_plugin/pose_display.cpp @@ -117,38 +117,39 @@ class PoseDisplaySelectionHandler : public SelectionHandler PoseDisplay::PoseDisplay() : pose_valid_(false) { shape_property_ = new EnumProperty("Shape", "Arrow", "Shape to display the pose as.", this, - SLOT(updateShapeChoice())); + &PoseDisplay::updateShapeChoice); shape_property_->addOption("Arrow", Arrow); shape_property_->addOption("Axes", Axes); color_property_ = new ColorProperty("Color", QColor(255, 25, 0), "Color to draw the arrow.", this, - SLOT(updateColorAndAlpha())); + &PoseDisplay::updateColorAndAlpha); alpha_property_ = new FloatProperty("Alpha", 1, "Amount of transparency to apply to the arrow.", this, - SLOT(updateColorAndAlpha())); + &PoseDisplay::updateColorAndAlpha); alpha_property_->setMin(0); alpha_property_->setMax(1); - shaft_length_property_ = new FloatProperty( - "Shaft Length", 1, "Length of the arrow's shaft, in meters.", this, SLOT(updateArrowGeometry())); + shaft_length_property_ = + new FloatProperty("Shaft Length", 1, "Length of the arrow's shaft, in meters.", this, + &PoseDisplay::updateArrowGeometry); // aleeper: default changed from 0.1 to match change in arrow.cpp shaft_radius_property_ = new FloatProperty("Shaft Radius", 0.05, "Radius of the arrow's shaft, in meters.", this, - SLOT(updateArrowGeometry())); + &PoseDisplay::updateArrowGeometry); head_length_property_ = new FloatProperty("Head Length", 0.3, "Length of the arrow's head, in meters.", - this, SLOT(updateArrowGeometry())); + this, &PoseDisplay::updateArrowGeometry); // aleeper: default changed from 0.2 to match change in arrow.cpp head_radius_property_ = new FloatProperty("Head Radius", 0.1, "Radius of the arrow's head, in meters.", - this, SLOT(updateArrowGeometry())); + this, &PoseDisplay::updateArrowGeometry); axes_length_property_ = new FloatProperty("Axes Length", 1, "Length of each axis, in meters.", this, - SLOT(updateAxisGeometry())); + &PoseDisplay::updateAxisGeometry); axes_radius_property_ = new FloatProperty("Axes Radius", 0.1, "Radius of each axis, in meters.", this, - SLOT(updateAxisGeometry())); + &PoseDisplay::updateAxisGeometry); } void PoseDisplay::onInitialize() diff --git a/src/rviz/default_plugin/pose_with_covariance_display.cpp b/src/rviz/default_plugin/pose_with_covariance_display.cpp index adc301f60f..a47e009a79 100644 --- a/src/rviz/default_plugin/pose_with_covariance_display.cpp +++ b/src/rviz/default_plugin/pose_with_covariance_display.cpp @@ -159,43 +159,44 @@ class PoseWithCovarianceDisplaySelectionHandler : public SelectionHandler PoseWithCovarianceDisplay::PoseWithCovarianceDisplay() : pose_valid_(false) { shape_property_ = new EnumProperty("Shape", "Arrow", "Shape to display the pose as.", this, - SLOT(updateShapeChoice())); + &PoseWithCovarianceDisplay::updateShapeChoice); shape_property_->addOption("Arrow", Arrow); shape_property_->addOption("Axes", Axes); color_property_ = new ColorProperty("Color", QColor(255, 25, 0), "Color to draw the arrow.", this, - SLOT(updateColorAndAlpha())); + &PoseWithCovarianceDisplay::updateColorAndAlpha); alpha_property_ = new FloatProperty("Alpha", 1, "Amount of transparency to apply to the arrow.", this, - SLOT(updateColorAndAlpha())); + &PoseWithCovarianceDisplay::updateColorAndAlpha); alpha_property_->setMin(0); alpha_property_->setMax(1); - shaft_length_property_ = new FloatProperty( - "Shaft Length", 1, "Length of the arrow's shaft, in meters.", this, SLOT(updateArrowGeometry())); + shaft_length_property_ = + new FloatProperty("Shaft Length", 1, "Length of the arrow's shaft, in meters.", this, + &PoseWithCovarianceDisplay::updateArrowGeometry); // aleeper: default changed from 0.1 to match change in arrow.cpp shaft_radius_property_ = new FloatProperty("Shaft Radius", 0.05, "Radius of the arrow's shaft, in meters.", this, - SLOT(updateArrowGeometry())); + &PoseWithCovarianceDisplay::updateArrowGeometry); head_length_property_ = new FloatProperty("Head Length", 0.3, "Length of the arrow's head, in meters.", - this, SLOT(updateArrowGeometry())); + this, &PoseWithCovarianceDisplay::updateArrowGeometry); // aleeper: default changed from 0.2 to match change in arrow.cpp head_radius_property_ = new FloatProperty("Head Radius", 0.1, "Radius of the arrow's head, in meters.", - this, SLOT(updateArrowGeometry())); + this, &PoseWithCovarianceDisplay::updateArrowGeometry); axes_length_property_ = new FloatProperty("Axes Length", 1, "Length of each axis, in meters.", this, - SLOT(updateAxisGeometry())); + &PoseWithCovarianceDisplay::updateAxisGeometry); axes_radius_property_ = new FloatProperty("Axes Radius", 0.1, "Radius of each axis, in meters.", this, - SLOT(updateAxisGeometry())); + &PoseWithCovarianceDisplay::updateAxisGeometry); covariance_property_ = new CovarianceProperty("Covariance", true, "Whether or not the covariances of the messages should be shown.", this, - SLOT(queueRender())); + &Display::queueRender); } void PoseWithCovarianceDisplay::onInitialize() diff --git a/src/rviz/default_plugin/range_display.cpp b/src/rviz/default_plugin/range_display.cpp index eca683f987..47be619063 100644 --- a/src/rviz/default_plugin/range_display.cpp +++ b/src/rviz/default_plugin/range_display.cpp @@ -46,13 +46,14 @@ namespace rviz RangeDisplay::RangeDisplay() { color_property_ = new ColorProperty("Color", Qt::white, "Color to draw the range.", this, - SLOT(updateColorAndAlpha())); + &RangeDisplay::updateColorAndAlpha); alpha_property_ = new FloatProperty("Alpha", 0.5, "Amount of transparency to apply to the range.", - this, SLOT(updateColorAndAlpha())); + this, &RangeDisplay::updateColorAndAlpha); - buffer_length_property_ = new IntProperty( - "Buffer Length", 1, "Number of prior measurements to display.", this, SLOT(updateBufferLength())); + buffer_length_property_ = + new IntProperty("Buffer Length", 1, "Number of prior measurements to display.", this, + &RangeDisplay::updateBufferLength); buffer_length_property_->setMin(1); } diff --git a/src/rviz/default_plugin/robot_model_display.cpp b/src/rviz/default_plugin/robot_model_display.cpp index a38b638b35..d6f79f9dd3 100644 --- a/src/rviz/default_plugin/robot_model_display.cpp +++ b/src/rviz/default_plugin/robot_model_display.cpp @@ -58,12 +58,12 @@ RobotModelDisplay::RobotModelDisplay() { visual_enabled_property_ = new Property("Visual Enabled", true, "Whether to display the visual representation of the robot.", - this, SLOT(updateVisualVisible())); + this, &RobotModelDisplay::updateVisualVisible); collision_enabled_property_ = new Property("Collision Enabled", false, "Whether to display the collision representation of the robot.", this, - SLOT(updateCollisionVisible())); + &RobotModelDisplay::updateCollisionVisible); update_rate_property_ = new FloatProperty("Update Interval", 0, "Interval at which to update the links, in seconds. " @@ -72,20 +72,20 @@ RobotModelDisplay::RobotModelDisplay() update_rate_property_->setMin(0); alpha_property_ = new FloatProperty("Alpha", 1, "Amount of transparency to apply to the links.", this, - SLOT(updateAlpha())); + &RobotModelDisplay::updateAlpha); alpha_property_->setMin(0.0); alpha_property_->setMax(1.0); robot_description_property_ = new StringProperty("Robot Description", "robot_description", "Name of the parameter to search for to load the robot description.", this, - SLOT(updateRobotDescription())); + &RobotModelDisplay::updateRobotDescription); tf_prefix_property_ = new StringProperty( "TF Prefix", "", "Robot Model normally assumes the link name is the same as the tf frame name. " " This option allows you to set a prefix. Mainly useful for multi-robot situations.", - this, SLOT(updateTfPrefix())); + this, &RobotModelDisplay::updateTfPrefix); } RobotModelDisplay::~RobotModelDisplay() @@ -155,7 +155,7 @@ void RobotModelDisplay::load() QString("Parameter [%1] does not exist, and was not found by searchParam()") .arg(robot_description_property_->getString())); // try again in a second - QTimer::singleShot(1000, this, SLOT(updateRobotDescription())); + QTimer::singleShot(1000, this, &RobotModelDisplay::updateRobotDescription); return; } } diff --git a/src/rviz/default_plugin/tf_display.cpp b/src/rviz/default_plugin/tf_display.cpp index 26216ddea7..994bafba51 100644 --- a/src/rviz/default_plugin/tf_display.cpp +++ b/src/rviz/default_plugin/tf_display.cpp @@ -96,7 +96,7 @@ void FrameSelectionHandler::createProperties(const Picked& /*obj*/, Property* pa new Property("Frame " + QString::fromStdString(frame_->name_), QVariant(), "", parent_property); enabled_property_ = new BoolProperty("Enabled", true, "", category_property_, - SLOT(updateVisibilityFromSelection()), frame_); + &FrameInfo::updateVisibilityFromSelection, frame_); parent_property_ = new StringProperty("Parent", "", "", category_property_); parent_property_->setReadOnly(true); @@ -235,15 +235,15 @@ TFDisplay::TFDisplay() : Display(), update_timer_(0.0f), changing_single_frame_e { show_names_property_ = new BoolProperty("Show Names", true, "Whether or not names should be shown next to the frames.", - this, SLOT(updateShowNames())); + this, &TFDisplay::updateShowNames); show_axes_property_ = new BoolProperty("Show Axes", true, "Whether or not the axes of each frame should be shown.", this, - SLOT(updateShowAxes())); + &TFDisplay::updateShowAxes); show_arrows_property_ = new BoolProperty("Show Arrows", true, "Whether or not arrows from child to parent should be shown.", - this, SLOT(updateShowArrows())); + this, &TFDisplay::updateShowArrows); scale_property_ = new FloatProperty("Marker Scale", 1, "Scaling factor for all names, axes and arrows.", this); @@ -273,7 +273,7 @@ TFDisplay::TFDisplay() : Display(), update_timer_(0.0f), changing_single_frame_e all_enabled_property_ = new BoolProperty("All Enabled", true, "Whether all the frames should be enabled or not.", - frames_category_, SLOT(allEnabledChanged()), this); + frames_category_, &TFDisplay::allEnabledChanged, this); tree_category_ = new Property( "Tree", QVariant(), "A tree-view of the frames, showing the parent/child relationships.", this); @@ -508,7 +508,7 @@ FrameInfo* TFDisplay::createFrame(const std::string& frame) info->enabled_property_ = new BoolProperty(QString::fromStdString(info->name_), true, "Enable or disable this individual frame.", nullptr, - SLOT(updateVisibilityFromFrame()), info); + &FrameInfo::updateVisibilityFromFrame, info); frames_category_->insertChildSorted(info->enabled_property_); info->parent_property_ = diff --git a/src/rviz/default_plugin/tools/goal_tool.cpp b/src/rviz/default_plugin/tools/goal_tool.cpp index f3869c2e23..c8576a2c1c 100644 --- a/src/rviz/default_plugin/tools/goal_tool.cpp +++ b/src/rviz/default_plugin/tools/goal_tool.cpp @@ -44,7 +44,7 @@ GoalTool::GoalTool() topic_property_ = new StringProperty("Topic", "goal", "The topic on which to publish navigation goals.", - getPropertyContainer(), SLOT(updateTopic()), this); + getPropertyContainer(), &GoalTool::updateTopic, this); } void GoalTool::onInitialize() diff --git a/src/rviz/default_plugin/tools/initial_pose_tool.cpp b/src/rviz/default_plugin/tools/initial_pose_tool.cpp index e6bbe4d8a6..1c52305a14 100644 --- a/src/rviz/default_plugin/tools/initial_pose_tool.cpp +++ b/src/rviz/default_plugin/tools/initial_pose_tool.cpp @@ -45,7 +45,7 @@ InitialPoseTool::InitialPoseTool() topic_property_ = new StringProperty("Topic", "initialpose", "The topic on which to publish initial pose estimates.", - getPropertyContainer(), SLOT(updateTopic()), this); + getPropertyContainer(), &InitialPoseTool::updateTopic, this); std_dev_x_ = new FloatProperty("X std deviation", 0.5, "X standard deviation for initial pose [m]", getPropertyContainer()); std_dev_y_ = new FloatProperty("Y std deviation", 0.5, "Y standard deviation for initial pose [m]", diff --git a/src/rviz/default_plugin/tools/interaction_tool.cpp b/src/rviz/default_plugin/tools/interaction_tool.cpp index 8f440af28e..488446a876 100644 --- a/src/rviz/default_plugin/tools/interaction_tool.cpp +++ b/src/rviz/default_plugin/tools/interaction_tool.cpp @@ -53,7 +53,7 @@ InteractionTool::InteractionTool() hide_inactive_property_ = new BoolProperty("Hide Inactive Objects", true, "While holding down a mouse button, hide all other Interactive Objects.", - getPropertyContainer(), SLOT(hideInactivePropertyChanged()), this); + getPropertyContainer(), &InteractionTool::hideInactivePropertyChanged, this); } InteractionTool::~InteractionTool() diff --git a/src/rviz/default_plugin/tools/point_tool.cpp b/src/rviz/default_plugin/tools/point_tool.cpp index bf15eb4f9a..a6d3cf5bd7 100644 --- a/src/rviz/default_plugin/tools/point_tool.cpp +++ b/src/rviz/default_plugin/tools/point_tool.cpp @@ -54,11 +54,11 @@ PointTool::PointTool() : Tool() topic_property_ = new StringProperty("Topic", "/clicked_point", "The topic on which to publish points.", - getPropertyContainer(), SLOT(updateTopic()), this); + getPropertyContainer(), &PointTool::updateTopic, this); auto_deactivate_property_ = new BoolProperty("Single click", true, "Switch away from this tool after one click.", - getPropertyContainer(), SLOT(updateAutoDeactivate()), this); + getPropertyContainer(), &PointTool::updateAutoDeactivate, this); updateTopic(); } diff --git a/src/rviz/default_plugin/view_controllers/fps_view_controller.cpp b/src/rviz/default_plugin/view_controllers/fps_view_controller.cpp index b24397bb3f..4afae59d5c 100644 --- a/src/rviz/default_plugin/view_controllers/fps_view_controller.cpp +++ b/src/rviz/default_plugin/view_controllers/fps_view_controller.cpp @@ -52,22 +52,22 @@ FPSViewController::FPSViewController() invert_z_->hide(); yaw_property_ = new FloatProperty("Yaw", 0, "Rotation of the camera around the Z (up) axis.", this, - SLOT(changedOrientation()), this); + &FPSViewController::changedOrientation, this); yaw_property_->setMax(Ogre::Math::PI); yaw_property_->setMin(-Ogre::Math::PI); pitch_property_ = new FloatProperty("Pitch", 0, "How much the camera is tipped downward.", this, - SLOT(changedOrientation()), this); + &FPSViewController::changedOrientation, this); pitch_property_->setMax(Ogre::Math::PI); pitch_property_->setMin(-Ogre::Math::PI); roll_property_ = new FloatProperty("Roll", 0, "Rotation about the camera's view direction.", this, - SLOT(changedOrientation()), this); + &FPSViewController::changedOrientation, this); roll_property_->setMax(Ogre::Math::PI); roll_property_->setMin(-Ogre::Math::PI); position_property_ = new VectorProperty("Position", Ogre::Vector3::ZERO, "Position of the camera.", - this, SLOT(changedPosition()), this); + this, &FPSViewController::changedPosition, this); } void FPSViewController::onInitialize() diff --git a/src/rviz/default_plugin/view_controllers/frame_view_controller.cpp b/src/rviz/default_plugin/view_controllers/frame_view_controller.cpp index b9741f7d6a..a3634d5071 100644 --- a/src/rviz/default_plugin/view_controllers/frame_view_controller.cpp +++ b/src/rviz/default_plugin/view_controllers/frame_view_controller.cpp @@ -55,7 +55,7 @@ FrameViewController::FrameViewController() { axis_property_ = new EnumProperty("Point towards", fmtAxis(6), "Point the camera along the given axis of the frame.", nullptr, - SLOT(changedAxis()), this); + &FrameViewController::changedAxis, this); axis_property_->addOption(ANY_AXIS, -1); this->addChild(axis_property_, yaw_property_->rowNumberInParent()); // x,y,z axes get integers from 1..6: +x, -x, +y, -y, +z, -z diff --git a/src/rviz/image/image_display_base.cpp b/src/rviz/image/image_display_base.cpp index f056a13f96..241dd3360d 100644 --- a/src/rviz/image/image_display_base.cpp +++ b/src/rviz/image/image_display_base.cpp @@ -43,13 +43,12 @@ namespace rviz { ImageDisplayBase::ImageDisplayBase() : Display(), sub_(), tf_filter_(), messages_received_(0) { - topic_property_ = - new RosTopicProperty("Image Topic", "", - QString::fromStdString(ros::message_traits::datatype()), - "sensor_msgs::Image topic to subscribe to.", this, SLOT(updateTopic())); + topic_property_ = new RosTopicProperty( + "Image Topic", "", QString::fromStdString(ros::message_traits::datatype()), + "sensor_msgs::Image topic to subscribe to.", this, &ImageDisplayBase::updateTopic); transport_property_ = new EnumProperty("Transport Hint", "raw", "Preferred method of sending images.", - this, SLOT(updateTopic())); + this, &ImageDisplayBase::updateTopic); connect(transport_property_, &EnumProperty::requestOptions, this, &ImageDisplayBase::fillTransportOptionList); @@ -59,13 +58,13 @@ ImageDisplayBase::ImageDisplayBase() : Display(), sub_(), tf_filter_(), messages "Advanced: set the size of the incoming message queue. Increasing this " "is useful if your incoming TF data is delayed significantly from your" " image data, but it can greatly increase memory usage if the messages are big.", - this, SLOT(updateQueueSize())); + this, &ImageDisplayBase::updateQueueSize); queue_size_property_->setMin(1); transport_property_->setStdString("raw"); - unreliable_property_ = - new BoolProperty("Unreliable", false, "Prefer UDP topic transport", this, SLOT(updateTopic())); + unreliable_property_ = new BoolProperty("Unreliable", false, "Prefer UDP topic transport", this, + &ImageDisplayBase::updateTopic); } ImageDisplayBase::~ImageDisplayBase() diff --git a/src/rviz/message_filter_display.h b/src/rviz/message_filter_display.h index 8b53e0b649..2c19f0b114 100644 --- a/src/rviz/message_filter_display.h +++ b/src/rviz/message_filter_display.h @@ -55,15 +55,15 @@ class RVIZ_EXPORT _RosTopicDisplay : public Display public: _RosTopicDisplay() { - topic_property_ = new RosTopicProperty("Topic", "", "", "", this, SLOT(updateTopic())); - unreliable_property_ = - new BoolProperty("Unreliable", false, "Prefer UDP topic transport", this, SLOT(updateTopic())); + topic_property_ = new RosTopicProperty("Topic", "", "", "", this, &_RosTopicDisplay::updateTopic); + unreliable_property_ = new BoolProperty("Unreliable", false, "Prefer UDP topic transport", this, + &_RosTopicDisplay::updateTopic); queue_size_property_ = new IntProperty("Queue Size", 10, "Size of TF message filter queue.\n" "Increasing this is useful if your TF data is delayed significantly " "w.r.t. your data, but it can greatly increase memory usage as well.", - this, SLOT(updateQueueSize())); + this, &_RosTopicDisplay::updateQueueSize); queue_size_property_->setMin(0); qRegisterMetaType>(); // required to send via queued connection } diff --git a/src/rviz/robot/robot.cpp b/src/rviz/robot/robot.cpp index 173b5e35a4..6300e8f393 100644 --- a/src/rviz/robot/robot.cpp +++ b/src/rviz/robot/robot.cpp @@ -81,20 +81,20 @@ Robot::Robot(Ogre::SceneNode* root_node, link_tree_->hide(); // hide until loaded link_tree_style_ = new EnumProperty("Link Tree Style", "", "How the list of links is displayed", - link_tree_, SLOT(changedLinkTreeStyle()), this); + link_tree_, &Robot::changedLinkTreeStyle, this); initLinkTreeStyle(); expand_tree_ = new BoolProperty("Expand Tree", false, "Expand or collapse link tree", link_tree_, - SLOT(changedExpandTree()), this); + &Robot::changedExpandTree, this); expand_link_details_ = new BoolProperty("Expand Link Details", false, "Expand link details (sub properties) to see all info for all links.", link_tree_, - SLOT(changedExpandLinkDetails()), this); + &Robot::changedExpandLinkDetails, this); expand_joint_details_ = new BoolProperty("Expand Joint Details", false, "Expand joint details (sub properties) to see all info for all joints.", - link_tree_, SLOT(changedExpandJointDetails()), this); + link_tree_, &Robot::changedExpandJointDetails, this); enable_all_links_ = new BoolProperty("All Links Enabled", true, "Turn all links on or off.", - link_tree_, SLOT(changedEnableAllLinks()), this); + link_tree_, &Robot::changedEnableAllLinks, this); } Robot::~Robot() diff --git a/src/rviz/robot/robot_joint.cpp b/src/rviz/robot/robot_joint.cpp index cc04b43416..85416f2ef7 100644 --- a/src/rviz/robot/robot_joint.cpp +++ b/src/rviz/robot/robot_joint.cpp @@ -53,13 +53,14 @@ RobotJoint::RobotJoint(Robot* robot, const urdf::JointConstSharedPtr& joint) , axes_(nullptr) , axis_(nullptr) { - joint_property_ = new Property(name_.c_str(), true, "", nullptr, SLOT(updateChildVisibility()), this); + joint_property_ = + new Property(name_.c_str(), true, "", nullptr, &RobotJoint::updateChildVisibility, this); joint_property_->setIcon(rviz::loadPixmap("package://rviz/icons/classes/RobotJoint.png")); details_ = new Property("Details", QVariant(), "", nullptr); axes_property_ = new Property("Show Axes", false, "Enable/disable showing the axes of this joint.", - joint_property_, SLOT(updateAxes()), this); + joint_property_, &RobotJoint::updateAxes, this); position_property_ = new VectorProperty("Position", Ogre::Vector3::ZERO, @@ -112,7 +113,7 @@ RobotJoint::RobotJoint(Robot* robot, const urdf::JointConstSharedPtr& joint) { show_axis_property_ = new Property("Show Joint Axis", false, "Enable/disable showing the axis of this joint.", - joint_property_, SLOT(updateAxis()), this); + joint_property_, &RobotJoint::updateAxis, this); axis_property_ = new VectorProperty("Joint Axis", Ogre::Vector3(joint->axis.x, joint->axis.y, joint->axis.z), diff --git a/src/rviz/robot/robot_link.cpp b/src/rviz/robot/robot_link.cpp index 359f8d64b5..7ffe26e1dc 100644 --- a/src/rviz/robot/robot_link.cpp +++ b/src/rviz/robot/robot_link.cpp @@ -168,20 +168,21 @@ RobotLink::RobotLink(Robot* robot, , is_selectable_(true) , material_mode_flags_(ORIGINAL) { - link_property_ = new Property(link->name.c_str(), true, "", nullptr, SLOT(updateVisibility()), this); + link_property_ = + new Property(link->name.c_str(), true, "", nullptr, &RobotLink::updateVisibility, this); link_property_->setIcon(rviz::loadPixmap("package://rviz/icons/classes/RobotLink.png")); details_ = new Property("Details", QVariant(), "", nullptr); alpha_property_ = new FloatProperty("Alpha", 1, "Amount of transparency to apply to this link.", - link_property_, SLOT(updateAlpha()), this); + link_property_, &RobotLink::updateAlpha, this); trail_property_ = new Property("Show Trail", false, "Enable/disable a 2 meter \"ribbon\" which follows this link.", - link_property_, SLOT(updateTrail()), this); + link_property_, &RobotLink::updateTrail, this); axes_property_ = new Property("Show Axes", false, "Enable/disable showing the axes of this link.", - link_property_, SLOT(updateAxes()), this); + link_property_, &RobotLink::updateAxes, this); position_property_ = new VectorProperty("Position", Ogre::Vector3::ZERO, diff --git a/src/rviz/view_controller.cpp b/src/rviz/view_controller.cpp index a65eb8d53a..14b002b9ee 100644 --- a/src/rviz/view_controller.cpp +++ b/src/rviz/view_controller.cpp @@ -58,7 +58,7 @@ ViewController::ViewController() near_clip_property_ = new FloatProperty("Near Clip Distance", 0.01f, "Anything closer to the camera than this threshold will not get rendered.", this, - SLOT(updateNearClipDistance())); + &ViewController::updateNearClipDistance); near_clip_property_->setMin(0.001); near_clip_property_->setMax(10000); @@ -66,19 +66,20 @@ ViewController::ViewController() "Render the main view in stereo if supported." " On Linux this requires a recent version of Ogre and" " an NVIDIA Quadro card with 3DVision glasses.", - this, SLOT(updateStereoProperties())); + this, &ViewController::updateStereoProperties); stereo_eye_swap_ = new BoolProperty("Swap Stereo Eyes", false, "Swap eyes if the monitor shows the left eye on the right.", - stereo_enable_, SLOT(updateStereoProperties()), this); + stereo_enable_, &ViewController::updateStereoProperties, this); stereo_eye_separation_ = new FloatProperty("Stereo Eye Separation", 0.06f, "Distance between eyes for stereo rendering.", - stereo_enable_, SLOT(updateStereoProperties()), this); - stereo_focal_distance_ = new FloatProperty("Stereo Focal Distance", 1.0f, - "Distance from eyes to screen. For stereo rendering.", - stereo_enable_, SLOT(updateStereoProperties()), this); + stereo_enable_, &ViewController::updateStereoProperties, this); + stereo_focal_distance_ = + new FloatProperty("Stereo Focal Distance", 1.0f, + "Distance from eyes to screen. For stereo rendering.", stereo_enable_, + &ViewController::updateStereoProperties, this); invert_z_ = new BoolProperty("Invert Z Axis", false, "Invert camera's Z axis for Z-down environments/models.", - this, SLOT(updateStereoProperties())); + this, &ViewController::updateStereoProperties); } void ViewController::initialize(DisplayContext* context) diff --git a/src/rviz/visualization_frame.cpp b/src/rviz/visualization_frame.cpp index 8acfa39ad9..65117fc6b1 100644 --- a/src/rviz/visualization_frame.cpp +++ b/src/rviz/visualization_frame.cpp @@ -140,11 +140,11 @@ VisualizationFrame::VisualizationFrame(QWidget* parent) reset_button->setText("Reset"); reset_button->setContentsMargins(0, 0, 0, 0); statusBar()->addPermanentWidget(reset_button, 0); - connect(reset_button, &QToolButton::clicked, this, &VisualizationFrame::reset); + connect(reset_button, &QToolButton::clicked, this, &VisualizationFrame::VisualizationFrame::reset); status_label_ = new QLabel(""); statusBar()->addPermanentWidget(status_label_, 1); - connect(this, &VisualizationFrame::statusUpdate, status_label_, &QLabel::setText); + connect(this, &VisualizationFrame::VisualizationFrame::statusUpdate, status_label_, &QLabel::setText); fps_label_ = new QLabel(""); fps_label_->setMinimumWidth(40); @@ -253,7 +253,7 @@ void VisualizationFrame::initialize(const QString& display_config_file) QPixmap splash_image(splash_path_); splash_ = new SplashScreen(splash_image); splash_->show(); - connect(this, &VisualizationFrame::statusUpdate, splash_, + connect(this, &VisualizationFrame::VisualizationFrame::statusUpdate, splash_, [this](const QString& message) { splash_->showMessage(message); }); } Q_EMIT statusUpdate("Initializing"); @@ -286,7 +286,8 @@ void VisualizationFrame::initialize(const QString& display_config_file) hide_left_dock_button_->setAutoRaise(true); hide_left_dock_button_->setCheckable(true); - connect(hide_left_dock_button_, &QToolButton::toggled, this, &VisualizationFrame::hideLeftDock); + connect(hide_left_dock_button_, &QToolButton::toggled, this, + &VisualizationFrame::VisualizationFrame::hideLeftDock); hide_right_dock_button_ = new QToolButton(); hide_right_dock_button_->setContentsMargins(0, 0, 0, 0); @@ -296,7 +297,8 @@ void VisualizationFrame::initialize(const QString& display_config_file) hide_right_dock_button_->setAutoRaise(true); hide_right_dock_button_->setCheckable(true); - connect(hide_right_dock_button_, &QToolButton::toggled, this, &VisualizationFrame::hideRightDock); + connect(hide_right_dock_button_, &QToolButton::toggled, this, + &VisualizationFrame::VisualizationFrame::hideRightDock); central_layout->addWidget(hide_left_dock_button_, 0); central_layout->addWidget(render_panel_, 1); @@ -324,7 +326,8 @@ void VisualizationFrame::initialize(const QString& display_config_file) manager_ = new VisualizationManager(render_panel_, this); manager_->setHelpPath(help_path_); - connect(manager_, &VisualizationManager::escapePressed, this, &VisualizationFrame::exitFullScreen); + connect(manager_, &VisualizationManager::escapePressed, this, + &VisualizationFrame::VisualizationFrame::exitFullScreen); // Periodically process events for the splash screen. QCoreApplication::processEvents(); @@ -338,10 +341,12 @@ void VisualizationFrame::initialize(const QString& display_config_file) connect(manager_, &VisualizationManager::configChanged, this, &VisualizationFrame::setDisplayConfigModified); - connect(tool_man, &ToolManager::toolAdded, this, &VisualizationFrame::addTool); - connect(tool_man, &ToolManager::toolRemoved, this, &VisualizationFrame::removeTool); - connect(tool_man, &ToolManager::toolRefreshed, this, &VisualizationFrame::refreshTool); - connect(tool_man, &ToolManager::toolChanged, this, &VisualizationFrame::indicateToolIsCurrent); + connect(tool_man, &ToolManager::toolAdded, this, &VisualizationFrame::VisualizationFrame::addTool); + connect(tool_man, &ToolManager::toolRemoved, this, &VisualizationFrame::VisualizationFrame::removeTool); + connect(tool_man, &ToolManager::toolRefreshed, this, + &VisualizationFrame::VisualizationFrame::refreshTool); + connect(tool_man, &ToolManager::toolChanged, this, + &VisualizationFrame::VisualizationFrame::indicateToolIsCurrent); manager_->initialize(); @@ -367,8 +372,10 @@ void VisualizationFrame::initialize(const QString& display_config_file) initialized_ = true; Q_EMIT statusUpdate("RViz is ready."); - connect(manager_, &VisualizationManager::preUpdate, this, &VisualizationFrame::updateFps); - connect(manager_, &VisualizationManager::statusUpdate, this, &VisualizationFrame::statusUpdate); + connect(manager_, &VisualizationManager::preUpdate, this, + &VisualizationFrame::VisualizationFrame::updateFps); + connect(manager_, &VisualizationManager::statusUpdate, this, + &VisualizationFrame::VisualizationFrame::statusUpdate); } void VisualizationFrame::initConfigs() @@ -447,32 +454,33 @@ void VisualizationFrame::initMenus() file_menu_ = menuBar()->addMenu("&File"); QAction* file_menu_open_action = - file_menu_->addAction("&Open Config", this, SLOT(onOpen()), QKeySequence("Ctrl+O")); + file_menu_->addAction("&Open Config", this, &VisualizationFrame::onOpen, QKeySequence("Ctrl+O")); this->addAction(file_menu_open_action); QAction* file_menu_save_action = - file_menu_->addAction("&Save Config", this, SLOT(onSave()), QKeySequence("Ctrl+S")); + file_menu_->addAction("&Save Config", this, &VisualizationFrame::onSave, QKeySequence("Ctrl+S")); this->addAction(file_menu_save_action); - QAction* file_menu_save_as_action = - file_menu_->addAction("Save Config &As", this, SLOT(onSaveAs()), QKeySequence("Ctrl+Shift+S")); + QAction* file_menu_save_as_action = file_menu_->addAction( + "Save Config &As", this, &VisualizationFrame::onSaveAs, QKeySequence("Ctrl+Shift+S")); this->addAction(file_menu_save_as_action); recent_configs_menu_ = file_menu_->addMenu("&Recent Configs"); - file_menu_->addAction("Save &Image", this, SLOT(onSaveImage())); + file_menu_->addAction("Save &Image", this, &VisualizationFrame::onSaveImage); if (show_choose_new_master_option_) { file_menu_->addSeparator(); - file_menu_->addAction("Change &Master", this, SLOT(changeMaster())); + file_menu_->addAction("Change &Master", this, &VisualizationFrame::changeMaster); } file_menu_->addSeparator(); - file_menu_->addAction("&Preferences", this, SLOT(openPreferencesDialog()), QKeySequence("Ctrl+P")); + file_menu_->addAction("&Preferences", this, &VisualizationFrame::openPreferencesDialog, + QKeySequence("Ctrl+P")); QAction* file_menu_quit_action = - file_menu_->addAction("&Quit", this, SLOT(close()), QKeySequence("Ctrl+Q")); + file_menu_->addAction("&Quit", this, &VisualizationFrame::close, QKeySequence("Ctrl+Q")); file_menu_quit_action->setObjectName("actQuit"); this->addAction(file_menu_quit_action); view_menu_ = menuBar()->addMenu("&Panels"); - view_menu_->addAction("Add &New Panel", this, SLOT(openNewPanelDialog())); + view_menu_->addAction("Add &New Panel", this, &VisualizationFrame::openNewPanelDialog); delete_view_menu_ = view_menu_->addMenu("&Delete Panel"); delete_view_menu_->setEnabled(false); @@ -485,10 +493,10 @@ void VisualizationFrame::initMenus() view_menu_->addSeparator(); QMenu* help_menu = menuBar()->addMenu("&Help"); - help_menu->addAction("Show &Help panel", this, SLOT(showHelpPanel())); - help_menu->addAction("Open rviz wiki in browser", this, SLOT(onHelpWiki())); + help_menu->addAction("Show &Help panel", this, &VisualizationFrame::showHelpPanel); + help_menu->addAction("Open rviz wiki in browser", this, &VisualizationFrame::onHelpWiki); help_menu->addSeparator(); - help_menu->addAction("&About", this, SLOT(onHelpAbout())); + help_menu->addAction("&About", this, &VisualizationFrame::onHelpAbout); } void VisualizationFrame::initToolbars() @@ -514,7 +522,8 @@ void VisualizationFrame::initToolbars() add_tool_button->setToolTip("Add a new tool"); add_tool_button->setIcon(loadPixmap("package://rviz/icons/plus.png")); toolbar_->addWidget(add_tool_button); - connect(add_tool_button, &QToolButton::clicked, this, &VisualizationFrame::openNewToolDialog); + connect(add_tool_button, &QToolButton::clicked, this, + &VisualizationFrame::VisualizationFrame::openNewToolDialog); remove_tool_menu_ = new QMenu(toolbar_); QToolButton* remove_tool_button = new QToolButton(); @@ -523,7 +532,8 @@ void VisualizationFrame::initToolbars() remove_tool_button->setToolTip("Remove a tool from the toolbar"); remove_tool_button->setIcon(loadPixmap("package://rviz/icons/minus.png")); toolbar_->addWidget(remove_tool_button); - connect(remove_tool_menu_, &QMenu::triggered, this, &VisualizationFrame::onToolbarRemoveTool); + connect(remove_tool_menu_, &QMenu::triggered, this, + &VisualizationFrame::VisualizationFrame::onToolbarRemoveTool); QMenu* button_style_menu = new QMenu(toolbar_); QAction* action_tool_button_icon_only = new QAction("Icon only", toolbar_actions_); @@ -545,7 +555,8 @@ void VisualizationFrame::initToolbars() button_style_button->setToolTip("Set toolbar style"); button_style_button->setIcon(loadPixmap("package://rviz/icons/visibility.svg")); toolbar_->addWidget(button_style_button); - connect(button_style_menu, &QMenu::triggered, this, &VisualizationFrame::onButtonStyleTool); + connect(button_style_menu, &QMenu::triggered, this, + &VisualizationFrame::VisualizationFrame::onButtonStyleTool); } void VisualizationFrame::hideDockImpl(Qt::DockWidgetArea area, bool hide) @@ -638,7 +649,8 @@ void VisualizationFrame::openNewPanelDialog() QDockWidget* dock = addPanelByName(display_name, class_id); if (dock) { - connect(dock, &QDockWidget::dockLocationChanged, this, &VisualizationFrame::onDockPanelChange); + connect(dock, &QDockWidget::dockLocationChanged, this, + &VisualizationFrame::VisualizationFrame::onDockPanelChange); } } manager_->startUpdate(); @@ -683,7 +695,8 @@ void VisualizationFrame::updateRecentConfigMenu() QString qdisplay_name = QString::fromStdString(display_name); QAction* action = new QAction(qdisplay_name, this); action->setData(QString::fromStdString(*it)); - connect(action, &QAction::triggered, this, &VisualizationFrame::onRecentConfigSelected); + connect(action, &QAction::triggered, this, + &VisualizationFrame::VisualizationFrame::onRecentConfigSelected); recent_configs_menu_->addAction(action); } } @@ -752,7 +765,8 @@ bool VisualizationFrame::loadDisplayConfigHelper(const std::string& full_path, c { dialog.reset(new LoadingDialog(this)); dialog->show(); - connect(this, &VisualizationFrame::statusUpdate, dialog.get(), &LoadingDialog::showMessage); + connect(this, &VisualizationFrame::VisualizationFrame::statusUpdate, dialog.get(), + &LoadingDialog::showMessage); // make the window correctly appear although running a long-term function QCoreApplication::processEvents(); @@ -950,7 +964,8 @@ void VisualizationFrame::loadPanels(const Config& config) // qobject_cast. if (dock) { - connect(dock, &QDockWidget::dockLocationChanged, this, &VisualizationFrame::onDockPanelChange); + connect(dock, &QDockWidget::dockLocationChanged, this, + &VisualizationFrame::VisualizationFrame::onDockPanelChange); Panel* panel = qobject_cast(dock->widget()); if (panel) { @@ -1125,7 +1140,8 @@ void VisualizationFrame::onSaveImage() { ScreenshotDialog* dialog = new ScreenshotDialog(this, render_panel_, QString::fromStdString(last_image_dir_)); - connect(dialog, &ScreenshotDialog::savedInDirectory, this, &VisualizationFrame::setImageSaveDirectory); + connect(dialog, &ScreenshotDialog::savedInDirectory, this, + &VisualizationFrame::VisualizationFrame::setImageSaveDirectory); dialog->show(); } @@ -1161,7 +1177,8 @@ void VisualizationFrame::addTool(Tool* tool) remove_tool_menu_->addAction(tool->getName()); - QObject::connect(tool, &Tool::nameChanged, this, &VisualizationFrame::onToolNameChanged); + QObject::connect(tool, &Tool::nameChanged, this, + &VisualizationFrame::VisualizationFrame::onToolNameChanged); } void VisualizationFrame::onToolNameChanged(const QString& name) @@ -1250,7 +1267,7 @@ void VisualizationFrame::showHelpPanel() { QDockWidget* dock = addPanelByName("Help", "rviz/Help"); show_help_action_ = dock->toggleViewAction(); - connect(dock, &QObject::destroyed, this, &VisualizationFrame::onHelpDestroyed); + connect(dock, &QObject::destroyed, this, &VisualizationFrame::VisualizationFrame::onHelpDestroyed); } else { @@ -1381,14 +1398,16 @@ QDockWidget* VisualizationFrame::addPanelByName(const QString& name, panel = new FailedPanel(class_id, error); } panel->setName(name); - connect(panel, &Panel::configChanged, this, &VisualizationFrame::setDisplayConfigModified); + connect(panel, &Panel::configChanged, this, + &VisualizationFrame::VisualizationFrame::setDisplayConfigModified); PanelRecord record; record.dock = addPane(name, panel, area, floating); record.panel = panel; record.name = name; - record.delete_action = delete_view_menu_->addAction(name, this, SLOT(onDeletePanel())); - connect(record.dock, &QObject::destroyed, this, &VisualizationFrame::onPanelDeleted); + record.delete_action = delete_view_menu_->addAction(name, this, &VisualizationFrame::onDeletePanel); + connect(record.dock, &QObject::destroyed, this, + &VisualizationFrame::VisualizationFrame::onPanelDeleted); custom_panels_.append(record); delete_view_menu_->setEnabled(true); @@ -1413,13 +1432,16 @@ VisualizationFrame::addPane(const QString& name, QWidget* panel, Qt::DockWidgetA // we want to know when that panel becomes visible connect(dock, &PanelDockWidget::visibilityChanged, this, &VisualizationFrame::onDockPanelVisibilityChange); - connect(this, &VisualizationFrame::fullScreenChange, dock, &PanelDockWidget::overrideVisibility); + connect(this, &VisualizationFrame::VisualizationFrame::fullScreenChange, dock, + &PanelDockWidget::overrideVisibility); QAction* toggle_action = dock->toggleViewAction(); view_menu_->addAction(toggle_action); - connect(toggle_action, &QAction::triggered, this, &VisualizationFrame::setDisplayConfigModified); - connect(dock, &PanelDockWidget::closed, this, &VisualizationFrame::setDisplayConfigModified); + connect(toggle_action, &QAction::triggered, this, + &VisualizationFrame::VisualizationFrame::setDisplayConfigModified); + connect(dock, &PanelDockWidget::closed, this, + &VisualizationFrame::VisualizationFrame::setDisplayConfigModified); dock->installEventFilter(geom_change_detector_); diff --git a/src/rviz/visualization_manager.cpp b/src/rviz/visualization_manager.cpp index 14fa4ef9d6..9bdb7ac63e 100644 --- a/src/rviz/visualization_manager.cpp +++ b/src/rviz/visualization_manager.cpp @@ -169,22 +169,21 @@ VisualizationManager::VisualizationManager(RenderPanel* render_panel, ip->setIcon(loadPixmap("package://rviz/icons/options.png")); global_options_ = ip; - fixed_frame_property_ = - new TfFrameProperty("Fixed Frame", "map", - "Frame into which all data is transformed before being displayed.", - global_options_, frame_manager_, false, SLOT(updateFixedFrame()), this); + fixed_frame_property_ = new TfFrameProperty( + "Fixed Frame", "map", "Frame into which all data is transformed before being displayed.", + global_options_, frame_manager_, false, &VisualizationManager::updateFixedFrame, this); background_color_property_ = new ColorProperty("Background Color", QColor(48, 48, 48), "Background color for the 3D view.", - global_options_, SLOT(updateBackgroundColor()), this); + global_options_, &VisualizationManager::updateBackgroundColor, this); fps_property_ = new IntProperty("Frame Rate", 30, "RViz will try to render this many frames per second.", - global_options_, SLOT(updateFps()), this); + global_options_, &VisualizationManager::updateFps, this); default_light_enabled_property_ = new BoolProperty("Default Light", true, "Light source attached to the current 3D view.", - global_options_, SLOT(updateDefaultLightVisible()), this); + global_options_, &VisualizationManager::updateDefaultLightVisible, this); root_display_group_->initialize( this); // only initialize() a Display after its sub-properties are created.