Skip to content

Commit

Permalink
Merge PR: #1790: Modernize to Qt5 slots
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed May 25, 2023
2 parents 93ac44b + f35dee1 commit 0612105
Show file tree
Hide file tree
Showing 96 changed files with 1,102 additions and 639 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ jobs:
CLANG_TIDY: true

env:
CXXFLAGS: "-Werror -Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-strict-aliasing -Wno-sign-compare"
CXXFLAGS: "-DRVIZ_DEPRECATE_QT4_SLOTS -Werror -Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-strict-aliasing -Wno-sign-compare"
UPSTREAM_WORKSPACE: github:rhaschke/python_qt_binding#silent-external-warnings
AFTER_INSTALL_TARGET_DEPENDENCIES: apt install -qq -y libogre-${{ matrix.ogre }}-dev
CATKIN_LINT: true
Expand Down
2 changes: 1 addition & 1 deletion src/image_view/image_view.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ void ImageView::showEvent(QShowEvent* event)
node->setVisible(true);

QTimer* timer = new QTimer(this);
connect(timer, SIGNAL(timeout()), this, SLOT(onTimer()));
connect(timer, &QTimer::timeout, this, &ImageView::onTimer);
timer->start(33);
}

Expand Down
32 changes: 13 additions & 19 deletions src/rviz/add_display_dialog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,20 +233,19 @@ AddDisplayDialog::AddDisplayDialog(DisplayFactory* factory,
setLayout(main_layout);

//***** Connections
connect(display_tree, SIGNAL(itemChanged(SelectionData*)), this,
SLOT(onDisplaySelected(SelectionData*)));
connect(display_tree, SIGNAL(itemActivated(QTreeWidgetItem*, int)), this, SLOT(accept()));
connect(display_tree, &DisplayTypeTree::itemChanged, this, &AddDisplayDialog::onDisplaySelected);
connect(display_tree, &DisplayTypeTree::itemActivated, this, &AddDisplayDialog::accept);

connect(topic_widget, SIGNAL(itemChanged(SelectionData*)), this, SLOT(onTopicSelected(SelectionData*)));
connect(topic_widget, SIGNAL(itemActivated(QTreeWidgetItem*, int)), this, SLOT(accept()));
connect(topic_widget, &TopicDisplayWidget::itemChanged, this, &AddDisplayDialog::onTopicSelected);
connect(topic_widget, &TopicDisplayWidget::itemActivated, this, &AddDisplayDialog::accept);

connect(button_box_, SIGNAL(accepted()), this, SLOT(accept()));
connect(button_box_, SIGNAL(rejected()), this, SLOT(reject()));
connect(button_box_, &QDialogButtonBox::accepted, this, &AddDisplayDialog::accept);
connect(button_box_, &QDialogButtonBox::rejected, this, &AddDisplayDialog::reject);

connect(tab_widget_, SIGNAL(currentChanged(int)), this, SLOT(onTabChanged(int)));
connect(tab_widget_, &QTabWidget::currentChanged, this, &AddDisplayDialog::onTabChanged);
if (display_name_output_)
{
connect(name_editor_, SIGNAL(textEdited(const QString&)), this, SLOT(onNameChanged()));
connect(name_editor_, &QLineEdit::textEdited, this, &AddDisplayDialog::onNameChanged);
}

button_box_->button(QDialogButtonBox::Ok)->setEnabled(isValid());
Expand Down Expand Up @@ -357,9 +356,7 @@ void AddDisplayDialog::accept()
DisplayTypeTree::DisplayTypeTree()
{
setHeaderHidden(true);

connect(this, SIGNAL(currentItemChanged(QTreeWidgetItem*, QTreeWidgetItem*)), this,
SLOT(onCurrentItemChanged(QTreeWidgetItem*, QTreeWidgetItem*)));
connect(this, &DisplayTypeTree::currentItemChanged, this, &DisplayTypeTree::onCurrentItemChanged);
}

void DisplayTypeTree::onCurrentItemChanged(QTreeWidgetItem* curr, QTreeWidgetItem* /*prev*/)
Expand Down Expand Up @@ -439,14 +436,12 @@ TopicDisplayWidget::TopicDisplayWidget()
layout->addWidget(tree_);
layout->addWidget(enable_hidden_box_);

connect(tree_, SIGNAL(currentItemChanged(QTreeWidgetItem*, QTreeWidgetItem*)), this,
SLOT(onCurrentItemChanged(QTreeWidgetItem*)));
// Forward signals from tree_
connect(tree_, SIGNAL(itemActivated(QTreeWidgetItem*, int)), this,
SIGNAL(itemActivated(QTreeWidgetItem*, int)));
connect(tree_, &QTreeWidget::currentItemChanged, this, &TopicDisplayWidget::onCurrentItemChanged);
connect(tree_, &QTreeWidget::itemActivated, this, &TopicDisplayWidget::itemActivated);

// Connect signal from checkbox
connect(enable_hidden_box_, SIGNAL(stateChanged(int)), this, SLOT(stateChanged(int)));
connect(enable_hidden_box_, &QCheckBox::stateChanged, this, &TopicDisplayWidget::stateChanged);

setLayout(layout);
}
Expand Down Expand Up @@ -531,8 +526,7 @@ void TopicDisplayWidget::fill(DisplayFactory* factory)
if (info.topic_suffixes.size() > 1)
{
EmbeddableComboBox* box = new EmbeddableComboBox(row, 1);
connect(box, SIGNAL(itemClicked(QTreeWidgetItem*, int)), this,
SLOT(onComboBoxClicked(QTreeWidgetItem*)));
connect(box, &EmbeddableComboBox::itemClicked, this, &TopicDisplayWidget::onComboBoxClicked);
for (int i = 0; i < info.topic_suffixes.size(); ++i)
{
box->addItem(info.topic_suffixes[i], info.datatypes[i]);
Expand Down
8 changes: 1 addition & 7 deletions src/rviz/add_display_dialog.h
Original file line number Diff line number Diff line change
Expand Up @@ -212,18 +212,12 @@ class EmbeddableComboBox : public QComboBox
public:
EmbeddableComboBox(QTreeWidgetItem* parent, int col) : parent_(parent), column_(col)
{
connect(this, SIGNAL(activated(int)), this, SLOT(onActivated(int)));
connect(this, qOverload<int>(&QComboBox::activated), this, [this] { itemClicked(parent_, column_); });
}

Q_SIGNALS:
void itemClicked(QTreeWidgetItem* item, int column);

private Q_SLOTS:
void onActivated(int /*index*/)
{
Q_EMIT itemClicked(parent_, column_);
}

private:
QTreeWidgetItem* parent_;
int column_;
Expand Down
16 changes: 8 additions & 8 deletions src/rviz/default_plugin/axes_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand Down
6 changes: 3 additions & 3 deletions src/rviz/default_plugin/camera_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,22 +84,22 @@ 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);

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);
}
Expand Down
46 changes: 21 additions & 25 deletions src/rviz/default_plugin/covariance_property.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,87 +44,83 @@ namespace rviz
CovarianceProperty::CovarianceProperty(const QString& name,
bool default_value,
const QString& description,
Property* parent,
const char* changed_slot,
QObject* receiver)
Property* parent)
// NOTE: changed() signal will only be initialized at the end of this constructor
: BoolProperty(name, default_value, description, parent)
{
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);

position_scale_property_ =
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);

orientation_offset_property_ = new FloatProperty(
"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, SIGNAL(changed()), this, SLOT(updateVisibility()));

// Connect changed() signal here instead of doing it through the initialization of BoolProperty().
// We do this here to make changed_slot be called _after_ updateVisibility()
if (changed_slot && (parent || receiver))
{
if (receiver)
connect(this, SIGNAL(changed()), receiver, changed_slot);
else
connect(this, SIGNAL(changed()), parent, changed_slot);
}
connect(this, &Property::changed, this, qOverload<>(&CovarianceProperty::updateVisibility));

setDisableChildrenIfFalse(true);
}
Expand Down
28 changes: 25 additions & 3 deletions src/rviz/default_plugin/covariance_property.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,31 @@ class CovarianceProperty : public rviz::BoolProperty
CovarianceProperty(const QString& name = "Covariance",
bool default_value = false,
const QString& description = QString(),
rviz::Property* parent = nullptr,
const char* changed_slot = nullptr,
QObject* receiver = nullptr);
rviz::Property* parent = nullptr);

template <typename Func, typename R>
CovarianceProperty(const QString& name,
bool default_value,
const QString& description,
rviz::Property* parent,
Func&& changed_slot,
const R* receiver)
: CovarianceProperty(name, default_value, description, parent)
{
connect(receiver, std::forward<Func>(changed_slot));
}

// this variant is required to allow omitting the receiver argument
template <typename Func, typename P>
CovarianceProperty(const QString& name,
bool default_value,
const QString& description,
P* parent,
Func&& changed_slot)
: CovarianceProperty(name, default_value, description, parent)
{
connect(parent, std::forward<Func>(changed_slot));
}

~CovarianceProperty() override;

Expand Down
32 changes: 17 additions & 15 deletions src/rviz/default_plugin/depth_cloud_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,18 +84,18 @@ 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>()),
"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_, SIGNAL(requestOptions(EnumProperty*)), this,
SLOT(fillTransportOptionList(EnumProperty*)));
connect(depth_transport_property_, &EnumProperty::requestOptions, this,
&DepthCloudDisplay::fillTransportOptionList);

depth_transport_property_->setStdString("raw");

Expand All @@ -106,14 +106,15 @@ DepthCloudDisplay::DepthCloudDisplay()
color_topic_property_ = new RosFilteredTopicProperty(
"Color Image Topic", "",
QString::fromStdString(ros::message_traits::datatype<sensor_msgs::Image>()),
"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_, SIGNAL(requestOptions(EnumProperty*)), this,
SLOT(fillTransportOptionList(EnumProperty*)));
connect(color_transport_property_, &EnumProperty::requestOptions, this,
&DepthCloudDisplay::fillTransportOptionList);

color_transport_property_->setStdString("raw");

Expand All @@ -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()
Expand Down
Loading

0 comments on commit 0612105

Please sign in to comment.