Skip to content

Commit

Permalink
Added a test
Browse files Browse the repository at this point in the history
Signed-off-by: Nate Koenig <[email protected]>
  • Loading branch information
Nate Koenig committed Jan 28, 2021
1 parent 9921e82 commit db69c56
Show file tree
Hide file tree
Showing 3 changed files with 127 additions and 0 deletions.
1 change: 1 addition & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ set(tests
battery_plugin.cc
breadcrumbs.cc
buoyancy.cc
collada_world_exporter.cc
components.cc
contact_system.cc
detachable_joint.cc
Expand Down
79 changes: 79 additions & 0 deletions test/integration/collada_world_exporter.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* 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.
*
*/

#include <gtest/gtest.h>

#include <ignition/common/Console.hh>
#include <ignition/common/Filesystem.hh>

#include "ignition/gazebo/Server.hh"
#include "ignition/gazebo/test_config.hh"

#include "helpers/UniqueTestDirectoryEnv.hh"

using namespace ignition;
using namespace gazebo;

/////////////////////////////////////////////////
class ColladaWorldExporterFixture : public ::testing::Test
{
public: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
}

public: void LoadWorld(const std::string &_path)
{
ServerConfig serverConfig;
serverConfig.SetResourceCache(test::UniqueTestDirectoryEnv::Path());
serverConfig.SetSdfFile(common::joinPaths(PROJECT_SOURCE_PATH, _path));

std::cout << "Loading: " << serverConfig.SdfFile() << std::endl;
this->server = std::make_unique<Server>(serverConfig);
EXPECT_FALSE(server->Running());
}

public: std::unique_ptr<Server> server;
};

/////////////////////////////////////////////////
TEST_F(ColladaWorldExporterFixture, ExportWorld)
{
this->LoadWorld("test/worlds/collada_world_exporter.sdf");

// The export directory shouldn't exist.
EXPECT_FALSE(common::exists("./collada_world_exporter_box_test"));

// Run one iteration which should export the world.
server->Run(true, 1, false);

// The export directory should now exist.
EXPECT_TRUE(common::exists("./collada_world_exporter_box_test"));

// Cleanup
common::removeAll("./collada_world_exporter_box_test");
}

/////////////////////////////////////////////////
/// Main
int main(int _argc, char **_argv)
{
::testing::InitGoogleTest(&_argc, _argv);
::testing::AddGlobalTestEnvironment(
new test::UniqueTestDirectoryEnv("save_world_test_cache"));
return RUN_ALL_TESTS();
}
47 changes: 47 additions & 0 deletions test/worlds/collada_world_exporter.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="collada_world_exporter_box_test">

<plugin
filename="ignition-gazebo-collada-world-exporter-system"
name="ignition::gazebo::systems::ColladaWorldExporter">
</plugin>

<model name="box">
<pose>0 0 0.5 0 0 0</pose>
<link name="box_link">
<inertial>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="box_collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>

<visual name="box_visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
<specular>1 0 0 1</specular>
</material>
</visual>
</link>
</model>
</world>
</sdf>

0 comments on commit db69c56

Please sign in to comment.