Skip to content

Commit

Permalink
Initial implementation of SDF checking feature
Browse files Browse the repository at this point in the history
This requires SDFormat API change gazebosim/sdformat#580.
  • Loading branch information
j-rivero committed Jun 2, 2021
1 parent b5f09f2 commit cfd4e9d
Show file tree
Hide file tree
Showing 5 changed files with 214 additions and 0 deletions.
10 changes: 10 additions & 0 deletions gazebo/Server.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include <boost/lexical_cast.hpp>
#include <boost/program_options.hpp>

#include <sdf/parser.hh>
#include <sdf/sdf.hh>

#include <ignition/math/Rand.hh>
Expand Down Expand Up @@ -69,6 +70,13 @@ namespace gazebo
{
struct ServerPrivate
{
void InspectSDFElement(const sdf::ElementPtr _elem) {
if (! sdf::recursiveSameTypeUniqueNames(_elem)) {
gzerr << "SDF is not valid, see errors above. "
<< "This can lead to an unexpected behaviour." << "\n";
}
}

/// \brief Boolean used to stop the server.
static bool stop;

Expand Down Expand Up @@ -446,6 +454,8 @@ bool Server::PreLoad()
bool Server::LoadImpl(sdf::ElementPtr _elem,
const std::string &_physics)
{
this->dataPtr->InspectSDFElement(_elem);

// If a physics engine is specified,
if (_physics.length())
{
Expand Down
1 change: 1 addition & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,7 @@ set(tests
rest_web.cc
saving_and_loading.cc
sdf.cc
sdf_errors.cc
sensor.cc
server_fixture.cc
sim_events.cc
Expand Down
111 changes: 111 additions & 0 deletions test/integration/sdf_errors.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,111 @@
/*
* 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 "gazebo/common/CommonIface.hh"
#include "gazebo/test/ServerFixture.hh"

using namespace gazebo;

class SDFLogsTest : public ServerFixture
{
public: void SetUp()
{
#ifndef _WIN32
const boost::filesystem::path home = common::getEnv("HOME");
#else
const boost::filesystem::path home = common::getEnv("HOMEPATH");
#endif
boost::filesystem::path log_path("/.gazebo/server-11345/default.log");
path = home / log_path;
}

public: void EXPECT_LOG_STRING(const std::string expected_text)
{
EXPECT_TRUE(log_string_search(expected_text)) <<
"The text '" + expected_text + "'" +
" was not found in the log. The test expects it to be there";
}

public: void EXPECT_NO_ERR_IN_LOG()
{
EXPECT_NO_LOG_STRING("[Err] ");
}

public: void EXPECT_NO_LOG_STRING(const std::string no_expected_text)
{
EXPECT_FALSE(log_string_search(no_expected_text)) <<
"The text '" + no_expected_text + "'" +
" was found in the log. The test does not expect it be there";
}

public: void EXPECT_ERR_IN_LOG()
{
EXPECT_LOG_STRING("[Err] ");
}

private: bool log_string_search(const std::string expected_text)
{
// Open the log file, and read back the string
std::ifstream ifs(path.string().c_str(), std::ios::in);
std::string loggedString;

while (!ifs.eof())
{
std::string line;
std::getline(ifs, line);
loggedString += line;
}

return loggedString.find(expected_text) != std::string::npos;
}

private: boost::filesystem::path path;
};

/////////////////////////////////////////////////
TEST_F(SDFLogsTest, EmptyWorldNoErrors)
{
Load("worlds/empty.world");
EXPECT_NO_ERR_IN_LOG();
}

/////////////////////////////////////////////////
TEST_F(SDFLogsTest, DuplicateSiblingSameType)
{
Load("worlds/test_sdf_err_sibling_same_type.world");

EXPECT_ERR_IN_LOG();
std::string sdfErrorString = "SDF is not valid";
EXPECT_LOG_STRING(sdfErrorString);
}

/////////////////////////////////////////////////
TEST_F(SDFLogsTest, DuplicateSiblingDifferentType)
{
// 1.6 SDF does not enforce different names for different types
Load("worlds/test_sdf_err_sibling_different_type.world");
EXPECT_NO_ERR_IN_LOG();
}

/////////////////////////////////////////////////
int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
46 changes: 46 additions & 0 deletions test/worlds/test_sdf16_err_sibling_different_type.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
<?xml version="1.0" encoding="UTF-8"?>

<sdf version='1.6'>
<world name='default'>

<model name='wall'>
<static>1</static>
<pose frame=''>0 0 1 0 0 1</pose>
<link name='wall'>
<collision name='repeated_name'>
<pose frame=''>-2.5 0 0 0 0 0</pose>
<geometry>
<box>
<size>5 0.2 2</size>
</box>
</geometry>
</collision>
<collision name='collision_1'>
<pose frame=''>-2.5 0 0 0 0 0</pose>
<geometry>
<box>
<size>5 0.2 2</size>
</box>
</geometry>
</collision>
<collision name='collision_2'>
<pose frame=''>-2.5 0 0 0 0 0</pose>
<geometry>
<box>
<size>5 0.2 2</size>
</box>
</geometry>
</collision>
<visual name='repeated_name'>
<pose frame=''>-2.5 0 0 0 0 0</pose>
<geometry>
<box>
<size>5 0.2 2</size>
</box>
</geometry>
</visual>
</link>
</model>

</world>
</sdf>
46 changes: 46 additions & 0 deletions test/worlds/test_sdf16_err_sibling_same_type.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
<?xml version="1.0" encoding="UTF-8"?>

<sdf version='1.6'>
<world name='default'>

<model name='wall'>
<static>1</static>
<pose frame=''>0 0 1 0 0 1</pose>
<link name='wall'>
<collision name='collision_1'>
<pose frame=''>-2.5 0 0 0 0 0</pose>
<geometry>
<box>
<size>5 0.2 2</size>
</box>
</geometry>
</collision>
<collision name='collision_1'>
<pose frame=''>-2.5 0 0 0 0 0</pose>
<geometry>
<box>
<size>5 0.2 2</size>
</box>
</geometry>
</collision>
<collision name='collision_1'>
<pose frame=''>-2.5 0 0 0 0 0</pose>
<geometry>
<box>
<size>5 0.2 2</size>
</box>
</geometry>
</collision>
<visual name='visual'>
<pose frame=''>-2.5 0 0 0 0 0</pose>
<geometry>
<box>
<size>5 0.2 2</size>
</box>
</geometry>
</visual>
</link>
</model>

</world>
</sdf>

0 comments on commit cfd4e9d

Please sign in to comment.