Skip to content

Commit

Permalink
Added tests.
Browse files Browse the repository at this point in the history
  • Loading branch information
StefanFabian committed May 1, 2020
1 parent 26e8def commit 51831ec
Show file tree
Hide file tree
Showing 9 changed files with 138 additions and 21 deletions.
3 changes: 2 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,8 @@ target_link_libraries(qml_ros_plugin ${catkin_LIBRARIES} Qt5::Core Qt5::Multimed
if (CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED)
find_package(ros_babel_fish_test_msgs REQUIRED)
include_directories(${ros_babel_fish_test_msgs_INCLUDE_DIRS})
find_package(std_srvs REQUIRED)
include_directories(${ros_babel_fish_test_msgs_INCLUDE_DIRS} ${std_srvs_INCLUDE_DIRS})

add_executable(${PROJECT_NAME}_test_action_server test/action_server.cpp)
target_link_libraries(${PROJECT_NAME}_test_action_server ${PROJECT_NAME})
Expand Down
4 changes: 2 additions & 2 deletions include/qml_ros_plugin/ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ Q_OBJECT

void operator=( const RosQml & ) = delete;

bool isInitialized();
bool isInitialized() const;

/*!
* Initializes the ros node with the given name and the command line arguments passed from the command line.
Expand Down Expand Up @@ -148,8 +148,8 @@ protected slots:
void updateSpinner();

QTimer timer_;
std::unique_ptr<ros::AsyncSpinner> spinner_;
std::shared_ptr<ros::CallbackQueue> callback_queue_;
std::unique_ptr<ros::AsyncSpinner> spinner_;
int threads_;
bool initialized_;
};
Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,7 @@
<test_depend>roscpp_tutorials</test_depend>
<test_depend>rostest</test_depend>
<test_depend>ros_babel_fish_test_msgs</test_depend>
<test_depend>std_srvs</test_depend>

<!-- The export tag contains other, unspecified, tags -->
<export>
Expand Down
9 changes: 7 additions & 2 deletions src/image_transport_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,13 +54,18 @@ void ImageTransportSubscriber::onRosShutdown()

void ImageTransportSubscriber::subscribe()
{
bool was_subscribed = subscribed_;
if ( subscribed_ ) unsubscribe();
// This makes sure we lazy subscribe and only subscribe if there is a surface to write to
if ( surface_ == nullptr ) return;
if ( !nh_->isReady()) return;
if ( topic_.isEmpty()) return;
if ( transport_ == nullptr ) return;
bool was_subscribed = subscribed_;
if ( subscribed_ )
{
blockSignals( true );
unsubscribe();
blockSignals( false );
}
// TODO Transport hints
image_transport::TransportHints transport_hints( default_transport_.toStdString());
try
Expand Down
2 changes: 1 addition & 1 deletion src/ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ RosQml::RosQml() : threads_( 1 ), initialized_( false )
timer_.start();
}

bool RosQml::isInitialized() { return initialized_; }
bool RosQml::isInitialized() const { return initialized_; }

void RosQml::init( const QString &name, quint32 options )
{
Expand Down
117 changes: 111 additions & 6 deletions test/communication.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include <geometry_msgs/Pose.h>
#include <roscpp_tutorials/TwoInts.h>
#include <std_srvs/Empty.h>

#include <QCoreApplication>
#include <QJSEngine>
Expand All @@ -35,15 +36,20 @@ struct MessageStorage
}
};

void processEvents()
{
QCoreApplication::processEvents();
ros::spinOnce();
RosQml::getInstance().spinOnce();
}

//! @param wait_count Max time to wait in increments of 33 ms
bool waitFor( const std::function<bool()> &pred, int wait_count = 10 )
{
while ( --wait_count > 0 )
{
if ( pred()) return true;
QCoreApplication::processEvents();
ros::spinOnce();
RosQml::getInstance().spinOnce();
processEvents();
ros::Duration( 0.033 ).sleep();
}
return false;
Expand Down Expand Up @@ -227,7 +233,7 @@ TEST( Communication, queryTopics )
EXPECT_TRUE( topics.contains( topic )) << topic.toStdString() << " is not in topics of type Pose";
}
QList<TopicInfo> topic_info = wrapper.queryTopicInfo();
for ( const QPair<QString, QString> &pair : QList<QPair<QString, QString>>{{ "/query_topics/pose1", "geometry_msgs/Pose" },
for ( const QPair<QString, QString> &pair : QList<QPair<QString, QString>>{{ "/query_topics/pose1", "geometry_msgs/Pose" },
{ "/query_topics/vector3", "geometry_msgs/Vector3" },
{ "/query_topics/point1", "geometry_msgs/Point" },
{ "/query_topics/point2", "geometry_msgs/Point" },
Expand All @@ -243,7 +249,8 @@ TEST( Communication, queryTopics )
EXPECT_EQ( info.datatype(), pair.second );
found = true;
}
EXPECT_TRUE( found ) << "Did not find " << pair.first.toStdString() << " in topic types." << std::endl << "Topics:" << debug_topics;
EXPECT_TRUE( found ) << "Did not find " << pair.first.toStdString() << " in topic types." << std::endl << "Topics:"
<< debug_topics;
}

EXPECT_EQ( wrapper.queryTopicType( "/query_topics/point1" ), "geometry_msgs/Point" );
Expand Down Expand Up @@ -274,12 +281,110 @@ TEST( Communication, serviceCall )
{ "b", 3 }} );
EXPECT_TRUE( service_called ) << "Service was not called!";
ASSERT_EQ( result.type(), QVariant::Map )
<< "Result was not world. Did the request fail? "
<< "Result was not map. Did the request fail? "
<< (result.type() == QVariant::Bool && !result.toBool() ? "Yes" : "No");
EXPECT_EQ( result.toMap()["sum"].toInt(), 4 )
<< "Contains 'sum'? " << (result.toMap().contains( "sum" ) ? "Yes" : "No");
}

TEST( Communication, serviceCallAsync )
{
QJSEngine engine;
QJSValue service_js = engine.newQObject( new qml_ros_plugin::Service );
auto *service = dynamic_cast<qml_ros_plugin::Service *>(service_js.toQObject());
ASSERT_NE( service, nullptr );
ros::NodeHandle nh;
ros::CallbackQueue queue;
nh.setCallbackQueue( &queue );
ros::AsyncSpinner spinner( 1, &queue );
bool service_called = false;
bool returned = false;
ros::ServiceServer server = nh.advertiseService<roscpp_tutorials::TwoIntsRequest, roscpp_tutorials::TwoIntsResponse>(
"/service",
boost::function<bool( roscpp_tutorials::TwoIntsRequest &, roscpp_tutorials::TwoIntsResponse & )>(
[ & ]( roscpp_tutorials::TwoIntsRequest &req, roscpp_tutorials::TwoIntsResponse &resp )
{
service_called = true;
ros::Duration( 1 ).sleep();
resp.sum = req.a + req.b;
returned = true;
return true;
} ));
spinner.start();
QJSValue obj = engine.newObject();
QJSValue callback = engine.evaluate( "function (watcher) { return function (resp) { watcher.result = resp; }; }" )
.call( { obj } );

service->callAsync( "/service", "roscpp_tutorials/TwoInts", {{ "a", 1 },
{ "b", 3 }}, callback );
ASSERT_TRUE( !returned );
waitFor( [ &returned ]() { return returned; }, 60 );
ASSERT_TRUE( returned );
processEvents();
ASSERT_TRUE( obj.hasProperty( "result" ));
QVariant result = obj.property( "result" ).toVariant();
EXPECT_TRUE( service_called ) << "Service was not called!";
ASSERT_EQ( result.type(), QVariant::Map )
<< "Result was not map. Did the request fail? "
<< (result.type() == QVariant::Bool && !result.toBool() ? "Yes" : "No") << std::endl
<< "Typename: " << result.typeName();
EXPECT_EQ( result.toMap()["sum"].toInt(), 4 )
<< "Contains 'sum'? " << (result.toMap().contains( "sum" ) ? "Yes" : "No");

service_called = false;
returned = false;
ros::ServiceServer server_false = nh.advertiseService<roscpp_tutorials::TwoIntsRequest, roscpp_tutorials::TwoIntsResponse>(
"/service_false",
boost::function<bool( roscpp_tutorials::TwoIntsRequest &, roscpp_tutorials::TwoIntsResponse & )>(
[ & ]( roscpp_tutorials::TwoIntsRequest &req, roscpp_tutorials::TwoIntsResponse &resp )
{
service_called = true;
returned = true;
return false;
} ));
obj = engine.newObject();
callback = engine.evaluate( "function (watcher) { return function (resp) { watcher.result = resp; }; }" )
.call( { obj } );

service->callAsync( "/service_false", "roscpp_tutorials/TwoInts", {{ "a", 1 },
{ "b", 3 }}, callback );
ASSERT_TRUE( !returned );
waitFor( [ &returned ]() { return returned; } );
ASSERT_TRUE( returned );
processEvents();
ASSERT_TRUE( obj.hasProperty( "result" ));
result = obj.property( "result" ).toVariant();
ASSERT_EQ( result.type(), QVariant::Bool ) << "Result was not bool. Typename: " << result.typeName();
EXPECT_FALSE( result.toBool() );

service_called = false;
returned = false;
ros::ServiceServer server_empty = nh.advertiseService<std_srvs::EmptyRequest , std_srvs::EmptyResponse>(
"/service_empty",
boost::function<bool( std_srvs::EmptyRequest &, std_srvs::EmptyResponse & )>(
[ & ]( std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &resp )
{
service_called = true;
returned = true;
return true;
} ));
obj = engine.newObject();
callback = engine.evaluate( "function (watcher) { return function (resp) { watcher.result = resp; }; }" )
.call( { obj } );

service->callAsync( "/service_empty", "std_srvs/Empty", {}, callback );
ASSERT_TRUE( !returned );
waitFor( [ &returned ]() { return returned; } );
ASSERT_TRUE( returned );
processEvents();
ASSERT_TRUE( obj.hasProperty( "result" ));
result = obj.property( "result" ).toVariant();
ASSERT_EQ( result.type(), QVariant::Bool ) << "Result was not bool. Typename: " << result.typeName();
EXPECT_TRUE( result.toBool() );


}

class ActionClientCallback : public QObject
{
Q_OBJECT
Expand Down
5 changes: 4 additions & 1 deletion test/image_transport_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,5 +149,8 @@ int main( int argc, char **argv )
testing::InitGoogleTest( &argc, argv );
QCoreApplication app( argc, argv );
ros::init( argc, argv, "test_image_transport_subscriber" );
return RUN_ALL_TESTS();
int result = RUN_ALL_TESTS();
ros::shutdown();
ros::Duration(0.5).sleep();
return result;
}
3 changes: 2 additions & 1 deletion test/logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,8 @@ TEST( Logging, log )
ASSERT_TRUE( wrapper->debug().isCallable());
wrapper->debug().call( { QJSValue( "Debug Message" ) } );
EXPECT_FALSE( waitFor( [ &log ]() { return !log.empty(); } )) << "Default level should not show debug messages.";
ASSERT_TRUE( wrapper->console().setLoggerLevel( wrapper->console().defaultName(), ros_console_levels::Debug ))
qml_ros_plugin::Console console = wrapper->console();
ASSERT_TRUE( console.setLoggerLevel( console.defaultName(), ros_console_levels::Debug ))
<< "Failed to set logging level.";
waitFor( []() { return false; } );

Expand Down
15 changes: 8 additions & 7 deletions test/package.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,20 +54,21 @@ using namespace qml_ros_plugin;
TEST( Package, package )
{
RosQmlSingletonWrapper wrapper;
QString path = wrapper.package().getPath( ROS_PACKAGE_NAME );
Package package = wrapper.package();
QString path = package.getPath( ROS_PACKAGE_NAME );
ASSERT_FALSE( path.isEmpty());
EXPECT_EQ( path.toStdString(), ros::package::getPath( ROS_PACKAGE_NAME ));

char *oldrpp = getenv( "ROS_PACKAGE_PATH" );
std::string package_path = path.toStdString() + "/test/test_packages";
setenv( "ROS_PACKAGE_PATH", package_path.c_str(), 1 );
path = wrapper.package().getPath( ROS_PACKAGE_NAME );
path = package.getPath( ROS_PACKAGE_NAME );
EXPECT_TRUE( path.isEmpty());

EXPECT_TRUE( listEquals( wrapper.package().getAll(),
EXPECT_TRUE( listEquals( package.getAll(),
std::vector<QString>{ "poor_people", "rich_people", "rick_astley", "world" } ));

QVariantMap plugins = wrapper.package().getPlugins( "world", "value" );
QVariantMap plugins = package.getPlugins( "world", "value" );
std::map<QString, std::vector<QString>> expected_plugins = {{ "rich_people", { "Nothing but despair" }},
{ "rick_astley", { "Never Gonna Give You Up" }}};
for ( const auto &key : plugins.keys())
Expand All @@ -76,7 +77,7 @@ TEST( Package, package )
EXPECT_TRUE( listEquals( plugins[key].toStringList(), expected_plugins[key] )) << key;
}

plugins = wrapper.package().getPlugins( "world", "wars" );
plugins = package.getPlugins( "world", "wars" );
expected_plugins = {{ "rich_people", { "true" }}};

for ( const auto &key : plugins.keys())
Expand All @@ -85,11 +86,11 @@ TEST( Package, package )
EXPECT_TRUE( listEquals( plugins[key].toStringList(), expected_plugins[key] )) << key;
}

QString output = wrapper.package().command( "depends-on poor_people" );
QString output = package.command( "depends-on poor_people" );
EXPECT_EQ( output.trimmed(), QString( "rich_people" ));

setenv( "ROS_PACKAGE_PATH", (package_path + "/not_existing_subfolder").c_str(), 1 );
ASSERT_TRUE( wrapper.package().getAll().empty());
ASSERT_TRUE( package.getAll().empty());

setenv( "ROS_PACKAGE_PATH", oldrpp, 1 );
}
Expand Down

0 comments on commit 51831ec

Please sign in to comment.