Skip to content

Commit

Permalink
Added regex filter field for TF display (#1032)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde authored Mar 15, 2024
1 parent 5a0bde5 commit cdf1c21
Show file tree
Hide file tree
Showing 5 changed files with 260 additions and 25 deletions.
2 changes: 2 additions & 0 deletions rviz_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,7 @@ set(rviz_common_headers_to_moc
include/rviz_common/properties/property_tree_model.hpp
include/rviz_common/properties/property_tree_with_help.hpp
include/rviz_common/properties/qos_profile_property.hpp
include/rviz_common/properties/regex_filter_property.hpp
include/rviz_common/properties/ros_topic_property.hpp
include/rviz_common/properties/status_list.hpp
include/rviz_common/properties/status_property.hpp
Expand Down Expand Up @@ -184,6 +185,7 @@ set(rviz_common_source_files
src/rviz_common/properties/ros_topic_property.cpp
src/rviz_common/properties/quaternion_property.cpp
src/rviz_common/properties/qos_profile_property.cpp
src/rviz_common/properties/regex_filter_property.cpp
src/rviz_common/properties/splitter_handle.cpp
src/rviz_common/properties/status_list.cpp
src/rviz_common/properties/status_property.cpp
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
/*
* Copyright (c) 2023, Open Source Robotics Foundation, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef RVIZ_COMMON__PROPERTIES__REGEX_FILTER_PROPERTY_HPP_
#define RVIZ_COMMON__PROPERTIES__REGEX_FILTER_PROPERTY_HPP_

#include <QValidator>
#include <QLineEdit>
#include <QToolTip>
#include <QWidget>

#include <regex>
#include <string>

#include "rviz_common/properties/string_property.hpp"
#include "rviz_common/visibility_control.hpp"

namespace rviz_common
{
namespace properties
{
class RVIZ_COMMON_PUBLIC RegexValidator : public QValidator
{
public:
explicit RegexValidator(QLineEdit * editor);

QValidator::State validate(QString & input, int & /*pos*/) const override;

private:
QLineEdit * editor_;
};

class RVIZ_COMMON_PUBLIC RegexFilterProperty : public StringProperty
{
public:
RegexFilterProperty(const QString & name, const std::string regex, Property * parent);

const std::regex & regex() const;
const std::string & regex_str() const;

QWidget * createEditor(QWidget * parent, const QStyleOptionViewItem & option) override;

private:
std::string default_;
std::regex regex_;
std::string regex_str_;

void onValueChanged();
};
} // end namespace properties
} // end namespace rviz_common
#endif // RVIZ_COMMON__PROPERTIES__REGEX_FILTER_PROPERTY_HPP_
108 changes: 108 additions & 0 deletions rviz_common/src/rviz_common/properties/regex_filter_property.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,108 @@
/*
* Copyright (c) 2023, Open Source Robotics Foundation, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#include "rviz_common/properties/regex_filter_property.hpp"

#include <QValidator>
#include <QLineEdit>
#include <QToolTip>
#include <QWidget>

#include <regex>

#include "rviz_common/properties/string_property.hpp"

namespace rviz_common
{
namespace properties
{
RegexValidator::RegexValidator(QLineEdit * editor)
: QValidator(editor), editor_(editor)
{
}

QValidator::State RegexValidator::validate(QString & input, int & /*pos*/) const
{
try {
std::regex(input.toLocal8Bit().constData());
editor_->setStyleSheet(QString());
QToolTip::hideText();
return QValidator::Acceptable;
} catch (const std::regex_error & e) {
editor_->setStyleSheet("background: #ffe4e4");
QToolTip::showText(editor_->mapToGlobal(QPoint(0, 5)), tr(e.what()), editor_, QRect(), 5000);
return QValidator::Intermediate;
}
}

void RegexFilterProperty::onValueChanged()
{
const auto & value = getString();
if (value.isEmpty()) {
regex_ = std::regex(default_);
regex_str_ = default_;
} else {
try {
regex_str_ = std::string(value.toLocal8Bit().constData());
regex_.assign(regex_str_, std::regex_constants::optimize);
} catch (const std::regex_error &) {
regex_ = std::regex(default_);
regex_str_ = default_;
}
}
}

RegexFilterProperty::RegexFilterProperty(
const QString & name, const std::string regex,
Property * parent)
: StringProperty(name, "", "regular expression", parent), default_(regex), regex_(regex),
regex_str_(regex)
{
QObject::connect(this, &RegexFilterProperty::changed, this, [this]() {onValueChanged();});
}

const std::regex & RegexFilterProperty::regex() const
{
return regex_;
}

const std::string & RegexFilterProperty::regex_str() const
{
return regex_str_;
}

QWidget * RegexFilterProperty::createEditor(QWidget * parent, const QStyleOptionViewItem & option)
{
auto * editor = qobject_cast<QLineEdit *>(StringProperty::createEditor(parent, option));
if (editor) {
editor->setValidator(new RegexValidator(editor));
}
return editor;
}
} // end namespace properties
} // end namespace rviz_common
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,7 @@ namespace properties
class BoolProperty;
class FloatProperty;
class QuaternionProperty;
class RegexFilterProperty;
class StringProperty;
class VectorProperty;
} // namespace properties
Expand Down Expand Up @@ -118,6 +119,8 @@ private Q_SLOTS:
FrameInfo * createFrame(const std::string & frame);
void updateFrame(FrameInfo * frame);
void deleteFrame(FrameInfo * frame, bool delete_properties);
typedef std::map<std::string, FrameInfo *> M_FrameInfo;
M_FrameInfo::iterator deleteFrame(M_FrameInfo::iterator it, bool delete_properties);
FrameInfo * getFrameInfo(const std::string & frame);
void clear();

Expand All @@ -129,7 +132,6 @@ private Q_SLOTS:
Ogre::SceneNode * arrows_node_;
Ogre::SceneNode * axes_node_;

typedef std::map<std::string, FrameInfo *> M_FrameInfo;
M_FrameInfo frames_;

typedef std::map<std::string, bool> M_EnabledState;
Expand All @@ -146,6 +148,9 @@ private Q_SLOTS:

rviz_common::properties::FloatProperty * scale_property_;

rviz_common::properties::RegexFilterProperty * filter_whitelist_property_;
rviz_common::properties::RegexFilterProperty * filter_blacklist_property_;

rviz_common::properties::Property * frames_category_;
rviz_common::properties::Property * tree_category_;

Expand All @@ -169,7 +174,6 @@ private Q_SLOTS:
void updateParentTreeProperty(FrameInfo * frame) const;

void deleteObsoleteFrames(std::set<FrameInfo *> & current_frames);
S_FrameInfo createOrUpdateFrames(const std::vector<std::string> & frames);

friend class FrameInfo;
};
Expand Down
Loading

0 comments on commit cdf1c21

Please sign in to comment.