Skip to content

Commit

Permalink
Added common test to rqt_gui_cpp and deprecate h headers (#311)
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 Jul 23, 2024
1 parent 6a24c40 commit 5ee2781
Show file tree
Hide file tree
Showing 8 changed files with 187 additions and 149 deletions.
5 changes: 5 additions & 0 deletions rqt_gui_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,11 @@ target_link_libraries(${PROJECT_NAME} PRIVATE
Qt5::Widgets
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

install(
TARGETS ${PROJECT_NAME}
EXPORT export_${PROJECT_NAME}
Expand Down
56 changes: 8 additions & 48 deletions rqt_gui_cpp/include/rqt_gui_cpp/plugin.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,54 +30,14 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef rqt_gui_cpp__Plugin_H
#define rqt_gui_cpp__Plugin_H
#ifndef RQT_GUI_CPP__PLUGIN_H_
#define RQT_GUI_CPP__PLUGIN_H_

#include <qt_gui_cpp/plugin.hpp>
#include <qt_gui_cpp/plugin_context.hpp>
#include <qt_gui_cpp/settings.hpp>
// *INDENT-OFF* (prevent uncrustify from adding indention below)
#warning Including header <rqt_gui_cpp/plugin.h> is deprecated, \
include <rqt_gui_cpp/plugin.hpp> instead.

#include <rclcpp/rclcpp.hpp>
// *INDENT-ON*
#include "./plugin.hpp"

namespace rqt_gui_cpp {

/**
* The base class for C++ plugins which use the ROS client library.
* A plugin must not call rclcpp::init() as this is performed once by the framework.
*/
class Plugin
: public qt_gui_cpp::Plugin
{

public:

Plugin()
: qt_gui_cpp::Plugin()
{}

/**
* Shutdown and clean up the plugin before unloading.
* I.e. unregister subscribers and stop timers.
*/
virtual void shutdownPlugin()
{}

virtual void passInNode(std::shared_ptr<rclcpp::Node> node)
{
node_ = node;
}

protected:

rclcpp::Node::SharedPtr node_;

private:

void onInit()
{}

};

} // namespace

#endif // rqt_gui_cpp__Plugin_H
#endif // RQT_GUI_CPP__PLUGIN_H_
80 changes: 80 additions & 0 deletions rqt_gui_cpp/include/rqt_gui_cpp/plugin.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
/*
* Copyright (c) 2011, Dirk Thomas, TU Darmstadt
* 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 TU Darmstadt 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 HOLDER 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 RQT_GUI_CPP__PLUGIN_HPP_
#define RQT_GUI_CPP__PLUGIN_HPP_

#include <memory>

#include <qt_gui_cpp/plugin.hpp>
#include <qt_gui_cpp/plugin_context.hpp>
#include <qt_gui_cpp/settings.hpp>

#include <rclcpp/rclcpp.hpp>

namespace rqt_gui_cpp
{

/**
* The base class for C++ plugins which use the ROS client library.
* A plugin must not call rclcpp::init() as this is performed once by the framework.
*/
class Plugin
: public qt_gui_cpp::Plugin
{
public:
Plugin()
: qt_gui_cpp::Plugin()
{}

/**
* Shutdown and clean up the plugin before unloading.
* I.e. unregister subscribers and stop timers.
*/
virtual void shutdownPlugin()
{}

virtual void passInNode(std::shared_ptr<rclcpp::Node> node)
{
node_ = node;
}

protected:
rclcpp::Node::SharedPtr node_;

private:
void onInit()
{}
};
} // namespace rqt_gui_cpp

#endif // RQT_GUI_CPP__PLUGIN_HPP_
3 changes: 3 additions & 0 deletions rqt_gui_cpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,9 @@
<build_depend>qtbase5-dev</build_depend>
<exec_depend version_gte="0.3.0">qt_gui_cpp</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
<qt_gui plugin="${prefix}/plugin.xml"/>
Expand Down
70 changes: 33 additions & 37 deletions rqt_gui_cpp/src/rqt_gui_cpp/nodelet_plugin_provider.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,26 +30,27 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#include "nodelet_plugin_provider.h"

#include "roscpp_plugin_provider.h"
#include "nodelet_plugin_provider.hpp"

#include <memory>
#include <stdexcept>
#include <string>

namespace rqt_gui_cpp {
#include "roscpp_plugin_provider.hpp"

NodeletPluginProvider::NodeletPluginProvider(const QString& export_tag, const QString& base_class_type)
: qt_gui_cpp::RosPluginlibPluginProvider<rqt_gui_cpp::Plugin>(export_tag, base_class_type)
namespace rqt_gui_cpp
{
NodeletPluginProvider::NodeletPluginProvider(
const QString & export_tag,
const QString & base_class_type)
: qt_gui_cpp::RosPluginlibPluginProvider<rqt_gui_cpp::Plugin>(export_tag, base_class_type)
, loader_initialized_(false)
, ros_spin_thread_(0)
{}

NodeletPluginProvider::~NodeletPluginProvider()
{
if (ros_spin_thread_ != 0)
{
if (ros_spin_thread_ != 0) {
ros_spin_thread_->abort = true;
ros_spin_thread_->exec_.remove_node(node_);
ros_spin_thread_->wait();
Expand All @@ -58,10 +59,9 @@ NodeletPluginProvider::~NodeletPluginProvider()
}
}

void NodeletPluginProvider::unload(void* instance)
void NodeletPluginProvider::unload(void * instance)
{
if (!instances_.contains(instance))
{
if (!instances_.contains(instance)) {
qCritical("rqt_gui_cpp::NodeletPluginProvider::unload() instance not found");
return;
}
Expand All @@ -73,14 +73,11 @@ void NodeletPluginProvider::unload(void* instance)

void NodeletPluginProvider::init_loader()
{

if (!loader_initialized_)
{
if (!loader_initialized_) {
loader_initialized_ = true;

// spawn ros spin thread
if (ros_spin_thread_ == 0)
{
if (ros_spin_thread_ == 0) {
ros_spin_thread_ = new RosSpinThread(this);
ros_spin_thread_->start();
}
Expand All @@ -91,26 +88,26 @@ void NodeletPluginProvider::init_loader()
// Initialize a node for execution to be shared by cpp plugins
node_ = rclcpp::Node::make_shared(name.str().c_str());
// Add our node to the executor for execution
if (ros_spin_thread_)
{
if (ros_spin_thread_) {
ros_spin_thread_->exec_.add_node(node_);
}
else
{
} else {
qWarning("rqt_gui_cpp::NodeletPluginProvider.init_loader: ros_spin_thread_ not initialized");
}
}

}

std::shared_ptr<Plugin> NodeletPluginProvider::create_plugin(const std::string& lookup_name, qt_gui_cpp::PluginContext* plugin_context)
std::shared_ptr<Plugin> NodeletPluginProvider::create_plugin(
const std::string & lookup_name,
qt_gui_cpp::PluginContext * plugin_context)
{
init_loader();

std::string nodelet_name = lookup_name + "_" + QString::number(plugin_context->serialNumber()).toStdString();
std::string nodelet_name = lookup_name + "_" +
QString::number(plugin_context->serialNumber()).toStdString();
instance_.reset();

instance_ = qt_gui_cpp::RosPluginlibPluginProvider<rqt_gui_cpp::Plugin>::create_plugin(lookup_name);
instance_ =
qt_gui_cpp::RosPluginlibPluginProvider<rqt_gui_cpp::Plugin>::create_plugin(lookup_name);
instance_->passInNode(node_);
instances_[&*instance_] = nodelet_name.c_str();

Expand All @@ -120,22 +117,24 @@ std::shared_ptr<Plugin> NodeletPluginProvider::create_plugin(const std::string&
}


void NodeletPluginProvider::init_plugin(const QString& plugin_id, qt_gui_cpp::PluginContext* plugin_context, qt_gui_cpp::Plugin* plugin)
void NodeletPluginProvider::init_plugin(
const QString & plugin_id,
qt_gui_cpp::PluginContext * plugin_context, qt_gui_cpp::Plugin * plugin)
{
qDebug("rqt_gui_cpp::NodeletPluginProvider::init_plugin()");
init_loader();

rqt_gui_cpp::Plugin* rqt_plugin = dynamic_cast<rqt_gui_cpp::Plugin*>(plugin);
if (!rqt_plugin)
{
rqt_gui_cpp::Plugin * rqt_plugin = dynamic_cast<rqt_gui_cpp::Plugin *>(plugin);
if (!rqt_plugin) {
throw std::runtime_error("plugin is not a rqt_plugin::Plugin");
}

qt_gui_cpp::RosPluginlibPluginProvider<rqt_gui_cpp::Plugin>::init_plugin(plugin_id, plugin_context, plugin);
qt_gui_cpp::RosPluginlibPluginProvider<rqt_gui_cpp::Plugin>::init_plugin(plugin_id,
plugin_context, plugin);
}

NodeletPluginProvider::RosSpinThread::RosSpinThread(QObject* parent)
: QThread(parent)
NodeletPluginProvider::RosSpinThread::RosSpinThread(QObject * parent)
: QThread(parent)
, abort(false)
{}

Expand All @@ -144,12 +143,9 @@ NodeletPluginProvider::RosSpinThread::~RosSpinThread()

void NodeletPluginProvider::RosSpinThread::run()
{
while (!abort)
{
while (!abort) {
// Spin the executor
exec_.spin_once();
}
}


}
} // namespace rqt_gui_cpp
Loading

0 comments on commit 5ee2781

Please sign in to comment.