Skip to content

Commit

Permalink
Adapt Property creation to use Qt5-style member-function pointers
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed Mar 31, 2023
1 parent b29cc02 commit 5164222
Show file tree
Hide file tree
Showing 38 changed files with 315 additions and 270 deletions.
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
30 changes: 19 additions & 11 deletions src/rviz/default_plugin/covariance_property.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,66 +50,74 @@ 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);

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, &Property::changed, this, qOverload<>(&CovarianceProperty::updateVisibility));
Expand Down
8 changes: 4 additions & 4 deletions src/rviz/default_plugin/covariance_property.h
Original file line number Diff line number Diff line change
Expand Up @@ -89,10 +89,10 @@ class CovarianceProperty : public rviz::BoolProperty
// 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)
bool default_value,
const QString& description,
P* parent,
Func&& changed_slot)
: CovarianceProperty(name, default_value, description, parent)
{
connect(parent, std::forward<Func>(changed_slot));
Expand Down
24 changes: 13 additions & 11 deletions src/rviz/default_plugin/depth_cloud_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>()),
"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);
Expand All @@ -106,10 +106,11 @@ 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_, &EnumProperty::requestOptions, this,
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
16 changes: 8 additions & 8 deletions src/rviz/default_plugin/effort_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -81,31 +81,31 @@ 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);

robot_description_property_ =
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);
}
Expand Down Expand Up @@ -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;
}
}
Expand Down
2 changes: 1 addition & 1 deletion src/rviz/default_plugin/grid_cells_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand Down
22 changes: 11 additions & 11 deletions src/rviz/default_plugin/grid_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,50 +53,50 @@ 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);

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()
Expand Down
8 changes: 4 additions & 4 deletions src/rviz/default_plugin/image_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand Down
Loading

0 comments on commit 5164222

Please sign in to comment.