Skip to content

Commit

Permalink
TF visualization plugin config (#32)
Browse files Browse the repository at this point in the history
* Add tf plugin gui config

* Use ign-gui plugin instead of pluginlib

* Add template tf gui config

Signed-off-by: Sarathkrishnan Ramesh <[email protected]>

* Add visibility options for frame axis, arrow and names

Signed-off-by: Sarathkrishnan Ramesh <[email protected]>

* Add more config options

* Set axes arrow head visibility

* Change marker scale

Signed-off-by: Sarathkrishnan Ramesh <[email protected]>

* Add tf frames to tree view

Signed-off-by: Sarathkrishnan Ramesh <[email protected]>

* Add option to set individual frame visibility

* Add checkboxes to tree view frame list

* Update documentation

Signed-off-by: Sarathkrishnan Ramesh <[email protected]>

* Add option to set visibility of all frames

Signed-off-by: Sarathkrishnan Ramesh <[email protected]>
  • Loading branch information
Sarath18 authored Jul 6, 2020
1 parent 3008b1b commit 1145250
Show file tree
Hide file tree
Showing 11 changed files with 809 additions and 359 deletions.
23 changes: 10 additions & 13 deletions ign_rviz/include/ignition/rviz/rviz.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,20 +66,17 @@ class RViz : public QObject
*/
Q_INVOKABLE void addTFDisplay()
{
try {
// Create new instance of plugin
DisplayPlugin<tf2_msgs::msg::TFMessage> tf_plugin =
std::dynamic_pointer_cast<plugins::MessageDisplay<tf2_msgs::msg::TFMessage>>(
plugin_loader.createSharedInstance(
"ignition/rviz/plugins/TFDisplay"));
tf_plugin->initialize(this->node);
tf_plugin->setFrameManager(this->frameManager);
tf_plugin->installEventFilter(ignition::gui::App()->findChild<ignition::gui::MainWindow *>());
// Load plugin
if (ignition::gui::App()->LoadPlugin("TFDisplay")) {
auto tfDisplayPlugins =
ignition::gui::App()->findChildren<plugins::MessageDisplay<tf2_msgs::msg::TFMessage> *>();
int tfDisplayCount = tfDisplayPlugins.size() - 1;

// Add the new plugin to the list
tf_plugins.push_back(tf_plugin);
} catch (pluginlib::PluginlibException & ex) {
std::cout << ex.what() << std::endl;
// Set frame manager and install event filter for recently added plugin
tfDisplayPlugins[tfDisplayCount]->initialize(this->node);
tfDisplayPlugins[tfDisplayCount]->setFrameManager(this->frameManager);
ignition::gui::App()->findChild<ignition::gui::MainWindow *>()->installEventFilter(
tfDisplayPlugins[tfDisplayCount]);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,15 +60,15 @@ class FrameManager : public QObject
* @param[out] _pose: Frame pose
* @return Pose validity (true if pose is valid, else false)
*/
bool getFramePose(std::string & _frame, ignition::math::Pose3d & _pose);
bool getFramePose(const std::string & _frame, ignition::math::Pose3d & _pose);

/**
* @brief Get parent frame pose (position and orientation)
* @param[in] _child: Child frame name
* @param[out] _pose: Parent frame pose
* @return Pose validity (true if pose is valid, else false)
*/
bool getParentPose(std::string & _child, ignition::math::Pose3d & _pose);
bool getParentPose(const std::string & _child, ignition::math::Pose3d & _pose);

/**
* @brief Get available tf frames
Expand Down
4 changes: 2 additions & 2 deletions ign_rviz_common/src/rviz/common/frame_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ void FrameManager::tf_callback(tf2_msgs::msg::TFMessage::SharedPtr _msg)
}

////////////////////////////////////////////////////////////////////////////////
bool FrameManager::getFramePose(std::string & _frame, ignition::math::Pose3d & _pose)
bool FrameManager::getFramePose(const std::string & _frame, ignition::math::Pose3d & _pose)
{
std::lock_guard<std::mutex>(this->tf_mutex_);

Expand All @@ -153,7 +153,7 @@ bool FrameManager::getFramePose(std::string & _frame, ignition::math::Pose3d & _
}

////////////////////////////////////////////////////////////////////////////////
bool FrameManager::getParentPose(std::string & _child, ignition::math::Pose3d & _pose)
bool FrameManager::getParentPose(const std::string & _child, ignition::math::Pose3d & _pose)
{
std::lock_guard<std::mutex>(this->tf_mutex_);

Expand Down
40 changes: 36 additions & 4 deletions ign_rviz_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@ include_directories(SYSTEM
qt5_add_resources(resources_RCC res/Plugins.qrc)

########################################################################

add_library(AxesDisplay SHARED ${headers_MOC}
include/ignition/rviz/plugins/AxesDisplay.hpp
include/ignition/rviz/plugins/message_display_base.hpp
Expand All @@ -67,7 +66,6 @@ target_include_directories(AxesDisplay
)

########################################################################

add_library(GlobalOptions SHARED ${headers_MOC}
include/ignition/rviz/plugins/GlobalOptions.hpp
src/rviz/plugins/GlobalOptions.cpp
Expand All @@ -93,16 +91,40 @@ target_include_directories(GlobalOptions
)

########################################################################
add_library(TFDisplay SHARED ${headers_MOC}
include/ignition/rviz/plugins/TFDisplay.hpp
include/ignition/rviz/plugins/message_display_base.hpp
src/rviz/plugins/TFDisplay.cpp
${resources_RCC}
)

ament_target_dependencies(TFDisplay
tf2_ros
ignition-gui4
ignition-math6
ignition-rendering4
ign_rviz_common
)

target_link_libraries(TFDisplay Qt5::Core Qt5::Qml Qt5::Quick Qt5::QuickControls2)

target_include_directories(TFDisplay
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
${Qt5Widgets_INCLUDE_DIRS}
${IGNITION-GUI_INCLUDE_DIRS}
)

set(ign_rviz_plugins_headers_to_moc
"include/ignition/rviz/plugins/message_display_base.hpp"
"include/ignition/rviz/plugins/tf_display.hpp"
"include/ignition/rviz/plugins/laser_scan_display.hpp"
)

########################################################################

add_library(ign_rviz_plugins SHARED
${ign_rviz_plugins_headers_to_moc}
src/rviz/plugins/tf_display.cpp
src/rviz/plugins/laser_scan_display.cpp
)

Expand Down Expand Up @@ -165,6 +187,16 @@ install(
INCLUDES DESTINATION include
)

ament_export_libraries(TFDisplay)

install(
TARGETS TFDisplay
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
INCLUDES DESTINATION include
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
Expand Down
180 changes: 180 additions & 0 deletions ign_rviz_plugins/include/ignition/rviz/plugins/TFDisplay.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,180 @@
// Copyright (c) 2020 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef IGNITION__RVIZ__PLUGINS__TFDISPLAY_HPP_
#define IGNITION__RVIZ__PLUGINS__TFDISPLAY_HPP_

#include <ignition/rendering.hh>
#include <tf2_msgs/msg/tf_message.hpp>

#include <QStandardItem>

#include <map>
#include <memory>
#include <mutex>
#include <string>
#include <vector>

#include "ignition/rviz/plugins/message_display_base.hpp"

namespace ignition
{
namespace rviz
{
namespace plugins
{
////////////////////////////////////////////////////////////////////////////////
class FrameModel : public QStandardItemModel
{
Q_OBJECT

public:
// Roles for tree view frames
enum FrameRoles
{
NameRole = Qt::UserRole + 1
};

// Constructor
explicit FrameModel(QObject * _parent = 0);

Q_INVOKABLE void addFrame(const QString & _name, QStandardItem * _parentItem);
Q_INVOKABLE QStandardItem * addParentRow(const QString & _name);

QVariant data(const QModelIndex & _index, int _role = Qt::DisplayRole) const;

protected:
QHash<int, QByteArray> roleNames() const;
};

////////////////////////////////////////////////////////////////////////////////
class TFDisplay : public MessageDisplay<tf2_msgs::msg::TFMessage>
{
Q_OBJECT

public:
/**
* Constructor for tf visualization plugin
*/
TFDisplay();

// Destructor
~TFDisplay();

// Documentation inherited
void LoadConfig(const tinyxml2::XMLElement * /*_pluginElem*/);

// Documentation Inherited
void initialize(rclcpp::Node::SharedPtr);

// Documentation Inherited
void callback(const tf2_msgs::msg::TFMessage::SharedPtr) {}

// Documentation inherited
void setTopic(std::string) {}

/**
* @brief Qt eventFilters. Original documentation can be found
* <a href="https://doc.qt.io/qt-5/qobject.html#eventFilter">here</a>
*/
bool eventFilter(QObject *, QEvent *);

// Documentation inherited
void setFrameManager(std::shared_ptr<common::FrameManager> _frameManager);

/**
* @brief Set axis visibility
* @param[in] _visible Axes visibility
*/
Q_INVOKABLE void showAxes(const bool & _visible);

/**
* @brief Set arrow visibility
* @param[in] _visible Arrow visibility
*/
Q_INVOKABLE void showArrows(const bool & _visible);

/**
* @brief Set frame name visibility
* @param[in] _visible Frame name visibility
*/
Q_INVOKABLE void showNames(const bool & _visible);

/**
* @brief Set axes arrow head visibility
* @param[in] _visible Axes arrow head visibility
*/
Q_INVOKABLE void showAxesHead(const bool & _visible);

/**
* @brief Set marker scale
* @param _scale TF visual marker scale
*/
Q_INVOKABLE void setMarkerScale(const float & _scale);

/**
* @brief Set frame visibility
* @param[in] _frame Frame name
* @param[in] _visible Frame visibility
*/
Q_INVOKABLE void setFrameVisibility(const QString & _frame, const bool & _visible);

protected:
/**
* @brief Create custom arrow visual for visualizing tf links
* @return tf arrow visual
*/
rendering::ArrowVisualPtr createTfArrow();

/**
* @brief Update tf visualization
*/
void updateTF();

/**
* @brief Creates a frame visual which includes an axis
* an arrow, and text visual
* @return A frame visual
*/
rendering::VisualPtr createVisualFrame();

/**
* @brief Update tree view and local frame list
*/
void refresh();

public:
// Tree view frame model
FrameModel * model;

private:
ignition::rendering::AxisVisualPtr axis;
ignition::rendering::RenderEngine * engine;
ignition::rendering::ScenePtr scene;
ignition::rendering::VisualPtr tfRootVisual;
std::mutex lock;
bool axesVisible;
bool arrowsVisible;
bool namesVisible;
bool axesHeadVisible;
float markerScale;
QStandardItem * parentRow;
std::map<std::string, bool> frameInfo;
};

} // namespace plugins
} // namespace rviz
} // namespace ignition

#endif // IGNITION__RVIZ__PLUGINS__TFDISPLAY_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,9 @@ class MessageDisplay : public MessageDisplayBase
rclcpp::Node::SharedPtr node;
std::string topic_name;
};

} // namespace plugins
} // namespace rviz
} // namespace ignition

#endif // IGNITION__RVIZ__PLUGINS__MESSAGE_DISPLAY_BASE_HPP_
Loading

0 comments on commit 1145250

Please sign in to comment.