From bc443fc04a7fb593d91c1f5a5a772bb32386b116 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Sun, 29 Jan 2017 23:04:38 -0500 Subject: [PATCH 01/14] Add SampleResourceRetriever class --- CMakeLists.txt | 9 ++ dart/config.hpp.in | 4 + dart/utils/SampleResourceRetriever.cpp | 132 ++++++++++++++++++ dart/utils/SampleResourceRetriever.hpp | 98 +++++++++++++ unittests/unit/CMakeLists.txt | 3 + .../unit/test_SampleResourceRetriever.cpp | 51 +++++++ 6 files changed, 297 insertions(+) create mode 100644 dart/utils/SampleResourceRetriever.cpp create mode 100644 dart/utils/SampleResourceRetriever.hpp create mode 100644 unittests/unit/test_SampleResourceRetriever.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 2a1c898c73d8..fed24dc4e5b2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -29,6 +29,8 @@ set(INCLUDE_INSTALL_DIR "include") set(LIBRARY_INSTALL_DIR "lib") set(CONFIG_INSTALL_DIR "share/${PROJECT_NAME}/cmake") +set(DART_DATA_INSTALL_REL_PATH "share/doc/${PROJECT_NAME}") + set(CMAKE_DEBUG_POSTFIX "d") set(CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/cmake") @@ -378,6 +380,13 @@ install(FILES ${PC_CONFIG_OUT} DESTINATION lib/pkgconfig) # Install a Catkin 'package.xml' file. This is required by REP-136. install(FILES package.xml DESTINATION share/${PROJECT_NAME}) +#=============================================================================== +# Install Misc. +#=============================================================================== + +install(DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/data" + DESTINATION ${DART_DATA_INSTALL_REL_PATH}) + #=============================================================================== # Uninstall #=============================================================================== diff --git a/dart/config.hpp.in b/dart/config.hpp.in index a1f52a125986..89adaaa3c121 100644 --- a/dart/config.hpp.in +++ b/dart/config.hpp.in @@ -60,9 +60,13 @@ #cmakedefine01 HAVE_BULLET_COLLISION #cmakedefine01 HAVE_FLANN +// Deprecated in DART 6.2 and will be removed in DART 7. #define DART_ROOT_PATH "@CMAKE_SOURCE_DIR@/" #define DART_DATA_PATH "@CMAKE_SOURCE_DIR@/data/" +#define DART_DATA_LOCAL_PATH "@CMAKE_SOURCE_DIR@/data/" +#define DART_DATA_GLOBAL_PATH "@CMAKE_INSTALL_PREFIX@/@DART_DATA_INSTALL_REL_PATH@/data/" + // See #451 #cmakedefine01 ASSIMP_AISCENE_CTOR_DTOR_DEFINED #cmakedefine01 ASSIMP_AIMATERIAL_CTOR_DTOR_DEFINED diff --git a/dart/utils/SampleResourceRetriever.cpp b/dart/utils/SampleResourceRetriever.cpp new file mode 100644 index 000000000000..025f604c8726 --- /dev/null +++ b/dart/utils/SampleResourceRetriever.cpp @@ -0,0 +1,132 @@ +/* + * Copyright (c) 2017, Graphics Lab, Georgia Tech Research Corporation + * Copyright (c) 2017, Personal Robotics Lab, Carnegie Mellon University + * All rights reserved. + * + * This file is provided under the following "BSD-style" License: + * 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. + * 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. + */ + +#include "dart/utils/SampleResourceRetriever.hpp" + +#include +#include +#include "dart/config.hpp" +#include "dart/common/Console.hpp" +#include "dart/common/LocalResourceRetriever.hpp" + +namespace dart { +namespace utils { + +//============================================================================== +SampleResourceRetriever::SampleResourceRetriever() + : mLocalRetriever(std::make_shared()) +{ + addDataDirectory(DART_DATA_LOCAL_PATH); + addDataDirectory(DART_DATA_GLOBAL_PATH); +} + +//============================================================================== +bool SampleResourceRetriever::exists(const common::Uri& uri) +{ + std::string relativePath; + if (!resolveDataUri(uri, relativePath)) + return false; + + for (const auto& dataPath : mDataDirectories) + { + common::Uri fileUri; + fileUri.fromPath(dataPath + relativePath); + + if (mLocalRetriever->exists(fileUri)) + return true; + } + return false; +} + +//============================================================================== +common::ResourcePtr SampleResourceRetriever::retrieve(const common::Uri& uri) +{ + std::string relativePath; + if (!resolveDataUri(uri, relativePath)) + return nullptr; + + for (const auto& dataPath : mDataDirectories) + { + common::Uri fileUri; + fileUri.fromPath(dataPath + relativePath); + + if (const auto resource = mLocalRetriever->retrieve(fileUri)) + return resource; + } + return nullptr; +} + +//============================================================================== +void SampleResourceRetriever::addDataDirectory( + const std::string& dataDirectory) +{ + // Strip a trailing slash. + std::string normalizedDataDirectory; + if (!dataDirectory.empty() && dataDirectory.back() == '/') + { + normalizedDataDirectory + = dataDirectory.substr(0, dataDirectory.size() - 1); + } + else + { + normalizedDataDirectory = dataDirectory; + } + + mDataDirectories.push_back(normalizedDataDirectory); +} + +//============================================================================== +bool SampleResourceRetriever::resolveDataUri( + const common::Uri& uri, + std::string& relativePath) const +{ + if (uri.mScheme.get_value_or("example") != "example") + return false; + + if (!uri.mAuthority) + { + dtwarn << "[SampleResourceRetriever::resolveDataUri] Invalid URI: The " + << "authority of '" << uri.toString() << "' should be 'example'.\n"; + return false; + } + + if (!uri.mPath) + { + dtwarn << "[SampleResourceRetriever::resolveDataUri] Failed extracting" + " relative path from URI '" << uri.toString() << "'.\n"; + return false; + } + relativePath = uri.mPath.get_value_or(""); + + return true; +} + +} // namespace utils +} // namespace dart diff --git a/dart/utils/SampleResourceRetriever.hpp b/dart/utils/SampleResourceRetriever.hpp new file mode 100644 index 000000000000..06f5e70b9d8c --- /dev/null +++ b/dart/utils/SampleResourceRetriever.hpp @@ -0,0 +1,98 @@ +/* + * Copyright (c) 2017, Graphics Lab, Georgia Tech Research Corporation + * Copyright (c) 2017, Personal Robotics Lab, Carnegie Mellon University + * All rights reserved. + * + * This file is provided under the following "BSD-style" License: + * 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. + * 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 DART_UTILS_SAMPLERESOURCERETRIEVER_HPP_ +#define DART_UTILS_SAMPLERESOURCERETRIEVER_HPP_ + +#include +#include +#include "dart/common/ResourceRetriever.hpp" + +namespace dart { +namespace utils { + +/// Retrieve resources from sample data URI. +/// +/// SampleResourceRetriever searches files in the following order: +/// 1) DART_DATA_LOCAL_PATH: path to the data directory in source +/// (e.g., [DART_SRC_ROOT]/data/). +/// 2) DART_DATA_GLOBAL_PATH: path to the data directory installed at a system +/// directory. The location can be varied depending on OS +/// (e.g., Linux: /usr/local/share/doc/dart/data/). +/// +/// Example of a sample data URI: +/// @code +/// "example://data/skel/shapes.skel" +/// \______________/ +/// | +/// file path with respect to +/// the data directory +/// @endcode +class SampleResourceRetriever : public common::ResourceRetriever +{ +public: + template + static std::shared_ptr create(Args&&... args) + { + return std::make_shared( + std::forward(args)...); + } + + /// Constructor. + SampleResourceRetriever(); + + /// Destructor. + virtual ~SampleResourceRetriever() = default; + + // Documentation inherited. + bool exists(const common::Uri& uri) override; + + // Documentation inherited. + common::ResourcePtr retrieve(const common::Uri& uri) override; + +private: + + void addDataDirectory(const std::string& packageDirectory); + + bool resolveDataUri(const common::Uri& uri, + std::string& relativePath) const; + +private: + common::ResourceRetrieverPtr mLocalRetriever; + + std::vector mDataDirectories; +}; + +using SampleResourceRetrieverPtr = std::shared_ptr; + +} // namespace utils +} // namespace dart + +#endif // ifndef DART_UTILS_SAMPLERESOURCERETRIEVER_HPP_ diff --git a/unittests/unit/CMakeLists.txt b/unittests/unit/CMakeLists.txt index d41d67b63781..c382eca5b331 100644 --- a/unittests/unit/CMakeLists.txt +++ b/unittests/unit/CMakeLists.txt @@ -24,6 +24,9 @@ if(TARGET dart-utils) dart_add_test("unit" test_CompositeResourceRetriever) target_link_libraries(test_CompositeResourceRetriever dart-utils) + dart_add_test("unit" test_SampleResourceRetriever) + target_link_libraries(test_SampleResourceRetriever dart-utils) + dart_add_test("unit" test_FileInfoWorld) target_link_libraries(test_FileInfoWorld dart-utils) diff --git a/unittests/unit/test_SampleResourceRetriever.cpp b/unittests/unit/test_SampleResourceRetriever.cpp new file mode 100644 index 000000000000..5974cf95e518 --- /dev/null +++ b/unittests/unit/test_SampleResourceRetriever.cpp @@ -0,0 +1,51 @@ +/* + * Copyright (c) 2017, Graphics Lab, Georgia Tech Research Corporation + * Copyright (c) 2017, Personal Robotics Lab, Carnegie Mellon University + * All rights reserved. + * + * This file is provided under the following "BSD-style" License: + * 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. + * 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. + */ + +#include +#include +#include "dart/utils/SampleResourceRetriever.hpp" + +using namespace dart; + +//============================================================================== +TEST(SampleResourceRetriever, SkelFileExists) +{ + auto retriever = utils::SampleResourceRetriever::create(); + EXPECT_TRUE(retriever->exists("example://data/skel/shapes.skel")); + auto sampleData = retriever->retrieve("example://data/skel/shapes.skel"); + EXPECT_TRUE(sampleData != nullptr); +} + +//============================================================================== +int main(int argc, char* argv[]) +{ + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} From 27efcdb1889833774947fa882b8f49d5dbc7bfb3 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Mon, 30 Jan 2017 15:42:33 -0500 Subject: [PATCH 02/14] Allow examples and tutorials to build out-of-source --- CMakeLists.txt | 7 +++++ dart/utils/SampleResourceRetriever.cpp | 2 +- dart/utils/SampleResourceRetriever.hpp | 2 +- dart/utils/SkelParser.cpp | 14 ++++++++- dart/utils/VskParser.cpp | 14 ++++++++- dart/utils/sdf/SdfParser.cpp | 17 ++++++++-- dart/utils/urdf/DartLoader.cpp | 2 ++ examples/CMakeLists.txt | 21 +++++++------ examples/addDeleteSkels/CMakeLists.txt | 25 ++++++++------- examples/addDeleteSkels/Main.cpp | 4 +-- examples/addDeleteSkels/MyWindow.hpp | 4 +-- examples/addDeleteSkels/README | 18 +++++++++++ examples/atlasSimbicon/CMakeLists.txt | 24 +++++++------- examples/atlasSimbicon/Controller.cpp | 8 ++--- examples/atlasSimbicon/Controller.hpp | 2 +- examples/atlasSimbicon/Humanoid.cpp | 4 +-- examples/atlasSimbicon/Humanoid.hpp | 2 +- examples/atlasSimbicon/Main.cpp | 10 +++--- examples/atlasSimbicon/MyWindow.cpp | 2 +- examples/atlasSimbicon/MyWindow.hpp | 6 ++-- examples/atlasSimbicon/README | 18 +++++++++++ examples/atlasSimbicon/State.cpp | 4 +-- examples/atlasSimbicon/State.hpp | 2 +- examples/atlasSimbicon/StateMachine.cpp | 4 +-- examples/atlasSimbicon/StateMachine.hpp | 2 +- examples/atlasSimbicon/TerminalCondition.cpp | 4 +-- examples/atlasSimbicon/TerminalCondition.hpp | 2 +- examples/bipedStand/CMakeLists.txt | 25 ++++++++------- examples/bipedStand/Controller.cpp | 2 +- examples/bipedStand/Controller.hpp | 2 +- examples/bipedStand/Main.cpp | 4 +-- examples/bipedStand/MyWindow.cpp | 2 +- examples/bipedStand/MyWindow.hpp | 6 ++-- examples/bipedStand/README | 18 +++++++++++ examples/hardcodedDesign/CMakeLists.txt | 25 ++++++++------- examples/hardcodedDesign/Main.cpp | 4 +-- examples/hardcodedDesign/MyWindow.cpp | 2 +- examples/hardcodedDesign/MyWindow.hpp | 4 +-- examples/hardcodedDesign/README | 18 +++++++++++ examples/hybridDynamics/CMakeLists.txt | 24 +++++++------- examples/hybridDynamics/Main.cpp | 4 +-- examples/hybridDynamics/MyWindow.hpp | 4 +-- examples/hybridDynamics/README | 18 +++++++++++ examples/jointConstraints/CMakeLists.txt | 24 +++++++------- examples/jointConstraints/Controller.cpp | 2 +- examples/jointConstraints/Controller.hpp | 2 +- examples/jointConstraints/Main.cpp | 6 ++-- examples/jointConstraints/MyWindow.cpp | 2 +- examples/jointConstraints/MyWindow.hpp | 6 ++-- examples/jointConstraints/README | 18 +++++++++++ examples/mixedChain/CMakeLists.txt | 24 +++++++------- examples/mixedChain/Main.cpp | 4 +-- examples/mixedChain/MyWindow.cpp | 2 +- examples/mixedChain/MyWindow.hpp | 4 +-- examples/mixedChain/README | 18 +++++++++++ .../operationalSpaceControl/CMakeLists.txt | 25 ++++++++------- .../operationalSpaceControl/Controller.cpp | 2 +- .../operationalSpaceControl/Controller.hpp | 2 +- examples/operationalSpaceControl/Main.cpp | 4 +-- examples/operationalSpaceControl/MyWindow.cpp | 2 +- examples/operationalSpaceControl/MyWindow.hpp | 4 +-- examples/operationalSpaceControl/README | 18 +++++++++++ examples/osg/CMakeLists.txt | 31 ------------------- examples/osg/osgAtlasSimbicon/CMakeLists.txt | 11 ------- examples/osg/osgTinkertoy/CMakeLists.txt | 11 ------- examples/osgExamples/CMakeLists.txt | 23 ++++++++++++++ .../osgExamples/osgAtlasPuppet/CMakeLists.txt | 14 +++++++++ examples/osgExamples/osgAtlasPuppet/README | 18 +++++++++++ .../osgAtlasPuppet}/osgAtlasPuppet.cpp | 2 +- .../AtlasSimbiconEventHandler.cpp | 0 .../AtlasSimbiconEventHandler.hpp | 0 .../osgAtlasSimbicon/AtlasSimbiconWidget.cpp | 0 .../osgAtlasSimbicon/AtlasSimbiconWidget.hpp | 0 .../AtlasSimbiconWorldNode.cpp | 0 .../AtlasSimbiconWorldNode.hpp | 0 .../osgAtlasSimbicon/CMakeLists.txt | 14 +++++++++ .../osgAtlasSimbicon/Controller.cpp | 0 .../osgAtlasSimbicon/Controller.hpp | 2 +- examples/osgExamples/osgAtlasSimbicon/README | 18 +++++++++++ .../osgAtlasSimbicon/State.cpp | 0 .../osgAtlasSimbicon/State.hpp | 2 +- .../osgAtlasSimbicon/StateMachine.cpp | 0 .../osgAtlasSimbicon/StateMachine.hpp | 2 +- .../osgAtlasSimbicon/TerminalCondition.cpp | 0 .../osgAtlasSimbicon/TerminalCondition.hpp | 2 +- .../osgAtlasSimbicon/main.cpp | 4 +-- .../osgExamples/osgDragAndDrop/CMakeLists.txt | 14 +++++++++ examples/osgExamples/osgDragAndDrop/README | 18 +++++++++++ .../osgDragAndDrop}/osgDragAndDrop.cpp | 0 examples/osgExamples/osgEmpty/CMakeLists.txt | 14 +++++++++ examples/osgExamples/osgEmpty/README | 18 +++++++++++ .../osgEmpty}/osgEmpty.cpp | 0 .../osgExamples/osgHubuPuppet/CMakeLists.txt | 14 +++++++++ examples/osgExamples/osgHubuPuppet/README | 18 +++++++++++ .../osgHubuPuppet}/osgHuboPuppet.cpp | 0 examples/osgExamples/osgImGui/CMakeLists.txt | 14 +++++++++ examples/osgExamples/osgImGui/README | 18 +++++++++++ .../osgImGui}/osgImGui.cpp | 0 .../osgOperationalSpaceControl/CMakeLists.txt | 14 +++++++++ .../osgOperationalSpaceControl/README | 18 +++++++++++ .../osgOperationalSpaceControl.cpp | 0 .../osgExamples/osgSoftBodies/CMakeLists.txt | 14 +++++++++ examples/osgExamples/osgSoftBodies/README | 18 +++++++++++ .../osgSoftBodies}/osgSoftBodies.cpp | 0 .../osgExamples/osgTinkertoy/CMakeLists.txt | 14 +++++++++ examples/osgExamples/osgTinkertoy/README | 18 +++++++++++ .../osgTinkertoy/TinkertoyWidget.cpp | 0 .../osgTinkertoy/TinkertoyWidget.hpp | 0 .../osgTinkertoy/TinkertoyWorldNode.cpp | 0 .../osgTinkertoy/TinkertoyWorldNode.hpp | 0 .../osgTinkertoy/main.cpp | 0 examples/rigidChain/CMakeLists.txt | 25 ++++++++------- examples/rigidChain/Main.cpp | 6 ++-- examples/rigidChain/MyWindow.cpp | 2 +- examples/rigidChain/MyWindow.hpp | 4 +-- examples/rigidChain/README | 18 +++++++++++ examples/rigidCubes/CMakeLists.txt | 25 ++++++++------- examples/rigidCubes/Main.cpp | 6 ++-- examples/rigidCubes/MyWindow.cpp | 2 +- examples/rigidCubes/MyWindow.hpp | 4 +-- examples/rigidCubes/README | 18 +++++++++++ examples/rigidLoop/CMakeLists.txt | 25 ++++++++------- examples/rigidLoop/Main.cpp | 6 ++-- examples/rigidLoop/MyWindow.cpp | 2 +- examples/rigidLoop/MyWindow.hpp | 4 +-- examples/rigidLoop/README | 18 +++++++++++ examples/rigidShapes/CMakeLists.txt | 25 ++++++++------- examples/rigidShapes/Main.cpp | 2 +- examples/rigidShapes/MyWindow.hpp | 4 +-- examples/rigidShapes/README | 18 +++++++++++ examples/simpleFrames/CMakeLists.txt | 25 ++++++++------- examples/simpleFrames/Main.cpp | 4 +-- examples/simpleFrames/README | 18 +++++++++++ examples/softBodies/CMakeLists.txt | 25 ++++++++------- examples/softBodies/Main.cpp | 4 +-- examples/softBodies/MyWindow.cpp | 2 +- examples/softBodies/MyWindow.hpp | 4 +-- examples/softBodies/README | 18 +++++++++++ examples/speedTest/CMakeLists.txt | 25 ++++++++------- examples/speedTest/Main.cpp | 2 +- examples/speedTest/README | 18 +++++++++++ examples/vehicle/CMakeLists.txt | 25 ++++++++------- examples/vehicle/Main.cpp | 6 ++-- examples/vehicle/MyWindow.cpp | 2 +- examples/vehicle/MyWindow.hpp | 4 +-- examples/vehicle/README | 18 +++++++++++ tutorials/CMakeLists.txt | 26 +++++++++++----- .../tutorialBiped-Finished/CMakeLists.txt | 15 +++++++++ tutorials/tutorialBiped-Finished/README | 18 +++++++++++ .../tutorialBiped-Finished.cpp | 4 +-- tutorials/tutorialBiped/CMakeLists.txt | 15 +++++++++ tutorials/tutorialBiped/README | 18 +++++++++++ .../{ => tutorialBiped}/tutorialBiped.cpp | 4 +-- .../CMakeLists.txt | 15 +++++++++ tutorials/tutorialCollisions-Finished/README | 18 +++++++++++ .../tutorialCollisions-Finished.cpp | 4 +-- tutorials/tutorialCollisions/CMakeLists.txt | 15 +++++++++ tutorials/tutorialCollisions/README | 18 +++++++++++ .../tutorialCollisions.cpp | 4 +-- .../tutorialDominoes-Finished/CMakeLists.txt | 15 +++++++++ tutorials/tutorialDominoes-Finished/README | 18 +++++++++++ .../tutorialDominoes-Finished.cpp | 4 +-- tutorials/tutorialDominoes/CMakeLists.txt | 15 +++++++++ tutorials/tutorialDominoes/README | 18 +++++++++++ .../tutorialDominoes.cpp | 4 +-- .../CMakeLists.txt | 15 +++++++++ .../tutorialMultiPendulum-Finished/README | 18 +++++++++++ .../tutorialMultiPendulum-Finished.cpp | 4 +-- .../tutorialMultiPendulum/CMakeLists.txt | 15 +++++++++ tutorials/tutorialMultiPendulum/README | 18 +++++++++++ .../tutorialMultiPendulum.cpp | 4 +-- unittests/comprehensive/test_Collision.cpp | 2 +- unittests/comprehensive/test_Dynamics.cpp | 2 +- unittests/comprehensive/test_Joints.cpp | 8 ++--- unittests/unit/test_FileInfoWorld.cpp | 2 +- .../unit/test_SampleResourceRetriever.cpp | 4 +-- unittests/unit/test_SdfParser.cpp | 20 ++++++------ unittests/unit/test_SkelParser.cpp | 6 ++-- 178 files changed, 1312 insertions(+), 401 deletions(-) create mode 100644 examples/addDeleteSkels/README create mode 100644 examples/atlasSimbicon/README create mode 100644 examples/bipedStand/README create mode 100644 examples/hardcodedDesign/README create mode 100644 examples/hybridDynamics/README create mode 100644 examples/jointConstraints/README create mode 100644 examples/mixedChain/README create mode 100644 examples/operationalSpaceControl/README delete mode 100644 examples/osg/CMakeLists.txt delete mode 100644 examples/osg/osgAtlasSimbicon/CMakeLists.txt delete mode 100644 examples/osg/osgTinkertoy/CMakeLists.txt create mode 100644 examples/osgExamples/CMakeLists.txt create mode 100644 examples/osgExamples/osgAtlasPuppet/CMakeLists.txt create mode 100644 examples/osgExamples/osgAtlasPuppet/README rename examples/{osg => osgExamples/osgAtlasPuppet}/osgAtlasPuppet.cpp (99%) rename examples/{osg => osgExamples}/osgAtlasSimbicon/AtlasSimbiconEventHandler.cpp (100%) rename examples/{osg => osgExamples}/osgAtlasSimbicon/AtlasSimbiconEventHandler.hpp (100%) rename examples/{osg => osgExamples}/osgAtlasSimbicon/AtlasSimbiconWidget.cpp (100%) rename examples/{osg => osgExamples}/osgAtlasSimbicon/AtlasSimbiconWidget.hpp (100%) rename examples/{osg => osgExamples}/osgAtlasSimbicon/AtlasSimbiconWorldNode.cpp (100%) rename examples/{osg => osgExamples}/osgAtlasSimbicon/AtlasSimbiconWorldNode.hpp (100%) create mode 100644 examples/osgExamples/osgAtlasSimbicon/CMakeLists.txt rename examples/{osg => osgExamples}/osgAtlasSimbicon/Controller.cpp (100%) rename examples/{osg => osgExamples}/osgAtlasSimbicon/Controller.hpp (99%) create mode 100644 examples/osgExamples/osgAtlasSimbicon/README rename examples/{osg => osgExamples}/osgAtlasSimbicon/State.cpp (100%) rename examples/{osg => osgExamples}/osgAtlasSimbicon/State.hpp (99%) rename examples/{osg => osgExamples}/osgAtlasSimbicon/StateMachine.cpp (100%) rename examples/{osg => osgExamples}/osgAtlasSimbicon/StateMachine.hpp (99%) rename examples/{osg => osgExamples}/osgAtlasSimbicon/TerminalCondition.cpp (100%) rename examples/{osg => osgExamples}/osgAtlasSimbicon/TerminalCondition.hpp (99%) rename examples/{osg => osgExamples}/osgAtlasSimbicon/main.cpp (96%) create mode 100644 examples/osgExamples/osgDragAndDrop/CMakeLists.txt create mode 100644 examples/osgExamples/osgDragAndDrop/README rename examples/{osg => osgExamples/osgDragAndDrop}/osgDragAndDrop.cpp (100%) create mode 100644 examples/osgExamples/osgEmpty/CMakeLists.txt create mode 100644 examples/osgExamples/osgEmpty/README rename examples/{osg => osgExamples/osgEmpty}/osgEmpty.cpp (100%) create mode 100644 examples/osgExamples/osgHubuPuppet/CMakeLists.txt create mode 100644 examples/osgExamples/osgHubuPuppet/README rename examples/{osg => osgExamples/osgHubuPuppet}/osgHuboPuppet.cpp (100%) create mode 100644 examples/osgExamples/osgImGui/CMakeLists.txt create mode 100644 examples/osgExamples/osgImGui/README rename examples/{osg => osgExamples/osgImGui}/osgImGui.cpp (100%) create mode 100644 examples/osgExamples/osgOperationalSpaceControl/CMakeLists.txt create mode 100644 examples/osgExamples/osgOperationalSpaceControl/README rename examples/{osg => osgExamples/osgOperationalSpaceControl}/osgOperationalSpaceControl.cpp (100%) create mode 100644 examples/osgExamples/osgSoftBodies/CMakeLists.txt create mode 100644 examples/osgExamples/osgSoftBodies/README rename examples/{osg => osgExamples/osgSoftBodies}/osgSoftBodies.cpp (100%) create mode 100644 examples/osgExamples/osgTinkertoy/CMakeLists.txt create mode 100644 examples/osgExamples/osgTinkertoy/README rename examples/{osg => osgExamples}/osgTinkertoy/TinkertoyWidget.cpp (100%) rename examples/{osg => osgExamples}/osgTinkertoy/TinkertoyWidget.hpp (100%) rename examples/{osg => osgExamples}/osgTinkertoy/TinkertoyWorldNode.cpp (100%) rename examples/{osg => osgExamples}/osgTinkertoy/TinkertoyWorldNode.hpp (100%) rename examples/{osg => osgExamples}/osgTinkertoy/main.cpp (100%) create mode 100644 examples/rigidChain/README create mode 100644 examples/rigidCubes/README create mode 100644 examples/rigidLoop/README create mode 100644 examples/rigidShapes/README create mode 100644 examples/simpleFrames/README create mode 100644 examples/softBodies/README create mode 100644 examples/speedTest/README create mode 100644 examples/vehicle/README create mode 100644 tutorials/tutorialBiped-Finished/CMakeLists.txt create mode 100644 tutorials/tutorialBiped-Finished/README rename tutorials/{ => tutorialBiped-Finished}/tutorialBiped-Finished.cpp (99%) create mode 100644 tutorials/tutorialBiped/CMakeLists.txt create mode 100644 tutorials/tutorialBiped/README rename tutorials/{ => tutorialBiped}/tutorialBiped.cpp (99%) create mode 100644 tutorials/tutorialCollisions-Finished/CMakeLists.txt create mode 100644 tutorials/tutorialCollisions-Finished/README rename tutorials/{ => tutorialCollisions-Finished}/tutorialCollisions-Finished.cpp (99%) create mode 100644 tutorials/tutorialCollisions/CMakeLists.txt create mode 100644 tutorials/tutorialCollisions/README rename tutorials/{ => tutorialCollisions}/tutorialCollisions.cpp (99%) create mode 100644 tutorials/tutorialDominoes-Finished/CMakeLists.txt create mode 100644 tutorials/tutorialDominoes-Finished/README rename tutorials/{ => tutorialDominoes-Finished}/tutorialDominoes-Finished.cpp (99%) create mode 100644 tutorials/tutorialDominoes/CMakeLists.txt create mode 100644 tutorials/tutorialDominoes/README rename tutorials/{ => tutorialDominoes}/tutorialDominoes.cpp (99%) create mode 100644 tutorials/tutorialMultiPendulum-Finished/CMakeLists.txt create mode 100644 tutorials/tutorialMultiPendulum-Finished/README rename tutorials/{ => tutorialMultiPendulum-Finished}/tutorialMultiPendulum-Finished.cpp (99%) create mode 100644 tutorials/tutorialMultiPendulum/CMakeLists.txt create mode 100644 tutorials/tutorialMultiPendulum/README rename tutorials/{ => tutorialMultiPendulum}/tutorialMultiPendulum.cpp (99%) diff --git a/CMakeLists.txt b/CMakeLists.txt index fed24dc4e5b2..f8152f2995ff 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -29,6 +29,11 @@ set(INCLUDE_INSTALL_DIR "include") set(LIBRARY_INSTALL_DIR "lib") set(CONFIG_INSTALL_DIR "share/${PROJECT_NAME}/cmake") +if(WIN32) + set() +else() +endif() + set(DART_DATA_INSTALL_REL_PATH "share/doc/${PROJECT_NAME}") set(CMAKE_DEBUG_POSTFIX "d") @@ -47,6 +52,8 @@ if(WIN32) set(CMAKE_INSTALL_PREFIX "C:/Golems" CACHE PATH "Install prefix" FORCE) endif() +message(STATUS "CMAKE_INSTALL_DOCDIR: ${CMAKE_INSTALL_DOCDIR}") + #=============================================================================== # Project settings #=============================================================================== diff --git a/dart/utils/SampleResourceRetriever.cpp b/dart/utils/SampleResourceRetriever.cpp index 025f604c8726..7a61a13b17bd 100644 --- a/dart/utils/SampleResourceRetriever.cpp +++ b/dart/utils/SampleResourceRetriever.cpp @@ -107,7 +107,7 @@ bool SampleResourceRetriever::resolveDataUri( const common::Uri& uri, std::string& relativePath) const { - if (uri.mScheme.get_value_or("example") != "example") + if (uri.mScheme.get_value_or("sample") != "sample") return false; if (!uri.mAuthority) diff --git a/dart/utils/SampleResourceRetriever.hpp b/dart/utils/SampleResourceRetriever.hpp index 06f5e70b9d8c..edc3ccfe4e45 100644 --- a/dart/utils/SampleResourceRetriever.hpp +++ b/dart/utils/SampleResourceRetriever.hpp @@ -49,7 +49,7 @@ namespace utils { /// /// Example of a sample data URI: /// @code -/// "example://data/skel/shapes.skel" +/// "sample://data/skel/shapes.skel" /// \______________/ /// | /// file path with respect to diff --git a/dart/utils/SkelParser.cpp b/dart/utils/SkelParser.cpp index fb5349567b90..1c101dce29d7 100644 --- a/dart/utils/SkelParser.cpp +++ b/dart/utils/SkelParser.cpp @@ -74,6 +74,8 @@ #include "dart/dynamics/Skeleton.hpp" #include "dart/dynamics/Marker.hpp" #include "dart/utils/XmlHelpers.hpp" +#include "dart/utils/CompositeResourceRetriever.hpp" +#include "dart/utils/SampleResourceRetriever.hpp" namespace dart { namespace utils { @@ -2406,9 +2408,19 @@ common::ResourceRetrieverPtr getRetriever( const common::ResourceRetrieverPtr& _retriever) { if(_retriever) + { return _retriever; + } else - return std::make_shared(); + { + auto newRetriever = std::make_shared(); + newRetriever->addSchemaRetriever( + "file", std::make_shared()); + newRetriever->addSchemaRetriever( + "sample", SampleResourceRetriever::create()); + + return newRetriever; + } } } // anonymous namespace diff --git a/dart/utils/VskParser.cpp b/dart/utils/VskParser.cpp index be063dac57f1..3c420357b040 100644 --- a/dart/utils/VskParser.cpp +++ b/dart/utils/VskParser.cpp @@ -42,6 +42,8 @@ #include "dart/common/LocalResourceRetriever.hpp" #include "dart/common/Uri.hpp" #include "dart/dynamics/dynamics.hpp" +#include "dart/utils/CompositeResourceRetriever.hpp" +#include "dart/utils/SampleResourceRetriever.hpp" #include "dart/utils/XmlHelpers.hpp" #define SCALE_VSK 1.0e-3 @@ -1022,9 +1024,19 @@ common::ResourceRetrieverPtr getRetriever( const common::ResourceRetrieverPtr& retriever) { if(retriever) + { return retriever; + } else - return std::make_shared(); + { + auto newRetriever = std::make_shared(); + newRetriever->addSchemaRetriever( + "file", std::make_shared()); + newRetriever->addSchemaRetriever( + "sample", SampleResourceRetriever::create()); + + return newRetriever; + } } } // anonymous namespace diff --git a/dart/utils/sdf/SdfParser.cpp b/dart/utils/sdf/SdfParser.cpp index b5702ef8725c..c52c7998b402 100644 --- a/dart/utils/sdf/SdfParser.cpp +++ b/dart/utils/sdf/SdfParser.cpp @@ -29,6 +29,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ +#include "dart/utils/sdf/SdfParser.hpp" + #include #include #include @@ -60,7 +62,8 @@ #include "dart/simulation/World.hpp" #include "dart/utils/SkelParser.hpp" #include "dart/utils/XmlHelpers.hpp" -#include "dart/utils/sdf/SdfParser.hpp" +#include "dart/utils/CompositeResourceRetriever.hpp" +#include "dart/utils/SampleResourceRetriever.hpp" namespace dart { namespace utils { @@ -1500,9 +1503,19 @@ common::ResourceRetrieverPtr getRetriever( const common::ResourceRetrieverPtr& retriever) { if(retriever) + { return retriever; + } else - return std::make_shared(); + { + auto newRetriever = std::make_shared(); + newRetriever->addSchemaRetriever( + "file", std::make_shared()); + newRetriever->addSchemaRetriever( + "sample", SampleResourceRetriever::create()); + + return newRetriever; + } } } // anonymous namespace diff --git a/dart/utils/urdf/DartLoader.cpp b/dart/utils/urdf/DartLoader.cpp index e4f60a3352e5..08e8df3c5b09 100644 --- a/dart/utils/urdf/DartLoader.cpp +++ b/dart/utils/urdf/DartLoader.cpp @@ -52,6 +52,7 @@ #include "dart/dynamics/CylinderShape.hpp" #include "dart/dynamics/MeshShape.hpp" #include "dart/simulation/World.hpp" +#include "dart/utils/SampleResourceRetriever.hpp" #include "dart/utils/urdf/URDFTypes.hpp" #include "dart/utils/urdf/urdf_world_parser.hpp" @@ -67,6 +68,7 @@ DartLoader::DartLoader() { mRetriever->addSchemaRetriever("file", mLocalRetriever); mRetriever->addSchemaRetriever("package", mPackageRetriever); + mRetriever->addSchemaRetriever("sample", SampleResourceRetriever::create()); } void DartLoader::addPackageDirectory(const std::string& _packageName, diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 072cb50f643b..550974634417 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -6,13 +6,16 @@ file(GLOB children RELATIVE ${CMAKE_CURRENT_LIST_DIR} "*") set(directories "") foreach(child ${children}) if(IS_DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/${child}") - if(EXISTS "${CMAKE_CURRENT_LIST_DIR}/${child}/CMakeLists.txt") - list(APPEND directories ${child}) - endif(EXISTS "${CMAKE_CURRENT_LIST_DIR}/${child}/CMakeLists.txt") - endif(IS_DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/${child}") -endforeach(child) -# List of all the subdirectories to include -foreach(EXAMPLE_DIR ${directories}) - add_subdirectory(${EXAMPLE_DIR}) -endforeach(EXAMPLE_DIR) + file(GLOB srcs "${CMAKE_CURRENT_LIST_DIR}/${child}/*.cpp") + + if(srcs) + add_executable(${child} ${srcs}) + target_link_libraries(${child} dart dart-utils-urdf dart-gui) + dart_add_example(${child}) + else() + add_subdirectory(${child}) + endif() + + endif() +endforeach() diff --git a/examples/addDeleteSkels/CMakeLists.txt b/examples/addDeleteSkels/CMakeLists.txt index a8463788049f..a76689cacc1b 100644 --- a/examples/addDeleteSkels/CMakeLists.txt +++ b/examples/addDeleteSkels/CMakeLists.txt @@ -1,11 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) + +project(addDeleteSkels) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/addDeleteSkels/Main.cpp b/examples/addDeleteSkels/Main.cpp index aff98c45b88d..f822aee07ebc 100644 --- a/examples/addDeleteSkels/Main.cpp +++ b/examples/addDeleteSkels/Main.cpp @@ -31,14 +31,14 @@ #include -#include "dart/dart.hpp" +#include #include "MyWindow.hpp" int main(int argc, char* argv[]) { // create and initialize the world dart::simulation::WorldPtr myWorld - = dart::utils::SkelParser::readWorld(DART_DATA_PATH"/skel/ground.skel"); + = dart::utils::SkelParser::readWorld("sample://data/skel/ground.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); myWorld->setGravity(gravity); diff --git a/examples/addDeleteSkels/MyWindow.hpp b/examples/addDeleteSkels/MyWindow.hpp index 550a0e3450df..8e336fa4217a 100644 --- a/examples/addDeleteSkels/MyWindow.hpp +++ b/examples/addDeleteSkels/MyWindow.hpp @@ -32,8 +32,8 @@ #ifndef EXAMPLES_ADDDELETESKELS_MYWINDOW_HPP_ #define EXAMPLES_ADDDELETESKELS_MYWINDOW_HPP_ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include /// \brief class MyWindow : public dart::gui::SimWindow { diff --git a/examples/addDeleteSkels/README b/examples/addDeleteSkels/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/addDeleteSkels/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/atlasSimbicon/CMakeLists.txt b/examples/atlasSimbicon/CMakeLists.txt index 567e459b394d..d408d8fcc9f8 100644 --- a/examples/atlasSimbicon/CMakeLists.txt +++ b/examples/atlasSimbicon/CMakeLists.txt @@ -1,12 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui dart-utils-urdf) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) +project(atlasSimbicon) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/atlasSimbicon/Controller.cpp b/examples/atlasSimbicon/Controller.cpp index 70c948d002e1..567e08f79f49 100644 --- a/examples/atlasSimbicon/Controller.cpp +++ b/examples/atlasSimbicon/Controller.cpp @@ -29,11 +29,11 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/atlasSimbicon/Controller.hpp" +#include "Controller.hpp" -#include "examples/atlasSimbicon/State.hpp" -#include "examples/atlasSimbicon/StateMachine.hpp" -#include "examples/atlasSimbicon/TerminalCondition.hpp" +#include "State.hpp" +#include "StateMachine.hpp" +#include "TerminalCondition.hpp" using namespace std; diff --git a/examples/atlasSimbicon/Controller.hpp b/examples/atlasSimbicon/Controller.hpp index 700c261d9fd9..35f03f7a1aef 100644 --- a/examples/atlasSimbicon/Controller.hpp +++ b/examples/atlasSimbicon/Controller.hpp @@ -36,7 +36,7 @@ #include -#include "dart/dart.hpp" +#include class StateMachine; diff --git a/examples/atlasSimbicon/Humanoid.cpp b/examples/atlasSimbicon/Humanoid.cpp index ecd380eb07fb..b0fd7a93a94b 100644 --- a/examples/atlasSimbicon/Humanoid.cpp +++ b/examples/atlasSimbicon/Humanoid.cpp @@ -29,9 +29,9 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/atlasSimbicon/Humanoid.hpp" +#include "Humanoid.hpp" -#include "examples/atlasSimbicon/State.hpp" +#include "State.hpp" // Macro for functions not implemented yet #define NOT_YET(FUNCTION) std::cout << #FUNCTION\ diff --git a/examples/atlasSimbicon/Humanoid.hpp b/examples/atlasSimbicon/Humanoid.hpp index 1a3712753dae..bf2e1772f1bb 100644 --- a/examples/atlasSimbicon/Humanoid.hpp +++ b/examples/atlasSimbicon/Humanoid.hpp @@ -37,7 +37,7 @@ #include -#include "dart/dart.hpp" +#include class State; diff --git a/examples/atlasSimbicon/Main.cpp b/examples/atlasSimbicon/Main.cpp index 416e5446295d..9495a1947e66 100644 --- a/examples/atlasSimbicon/Main.cpp +++ b/examples/atlasSimbicon/Main.cpp @@ -31,10 +31,10 @@ #include -#include "dart/dart.hpp" +#include -#include "examples/atlasSimbicon/MyWindow.hpp" -#include "examples/atlasSimbicon/Controller.hpp" +#include "MyWindow.hpp" +#include "Controller.hpp" using namespace std; using namespace Eigen; @@ -52,9 +52,7 @@ int main(int argc, char* argv[]) // Load ground and Atlas robot and add them to the world DartLoader urdfLoader; SkeletonPtr ground = urdfLoader.parseSkeleton( - DART_DATA_PATH"sdf/atlas/ground.urdf"); -// SkeletonPtr atlas = SoftSdfParser::readSkeleton( -// DART_DATA_PATH"sdf/atlas/atlas_v3_no_head.sdf"); + "sample://data/sdf/atlas/ground.urdf"); SkeletonPtr atlas = SdfParser::readSkeleton( DART_DATA_PATH"sdf/atlas/atlas_v3_no_head_soft_feet.sdf"); myWorld->addSkeleton(atlas); diff --git a/examples/atlasSimbicon/MyWindow.cpp b/examples/atlasSimbicon/MyWindow.cpp index 00f2a5738b7e..bd5d12107395 100644 --- a/examples/atlasSimbicon/MyWindow.cpp +++ b/examples/atlasSimbicon/MyWindow.cpp @@ -29,7 +29,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/atlasSimbicon/MyWindow.hpp" +#include "MyWindow.hpp" //============================================================================== MyWindow::MyWindow(Controller* _controller) diff --git a/examples/atlasSimbicon/MyWindow.hpp b/examples/atlasSimbicon/MyWindow.hpp index a83a1eed5c4f..287df8b963be 100644 --- a/examples/atlasSimbicon/MyWindow.hpp +++ b/examples/atlasSimbicon/MyWindow.hpp @@ -32,10 +32,10 @@ #ifndef EXAMPLES_ATLASSIMBICON_MYWINDOW_HPP_ #define EXAMPLES_ATLASSIMBICON_MYWINDOW_HPP_ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include -#include "examples/atlasSimbicon/Controller.hpp" +#include "Controller.hpp" /// \brief class MyWindow class MyWindow : public dart::gui::SimWindow diff --git a/examples/atlasSimbicon/README b/examples/atlasSimbicon/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/atlasSimbicon/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/atlasSimbicon/State.cpp b/examples/atlasSimbicon/State.cpp index a74f5f053447..644cdce389be 100644 --- a/examples/atlasSimbicon/State.cpp +++ b/examples/atlasSimbicon/State.cpp @@ -29,9 +29,9 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/atlasSimbicon/State.hpp" +#include "State.hpp" -#include "examples/atlasSimbicon/TerminalCondition.hpp" +#include "TerminalCondition.hpp" // Macro for functions not implemented yet #define NOT_YET(FUNCTION) std::cout << #FUNCTION\ diff --git a/examples/atlasSimbicon/State.hpp b/examples/atlasSimbicon/State.hpp index 8b7fe666f5b0..106ae63245f8 100644 --- a/examples/atlasSimbicon/State.hpp +++ b/examples/atlasSimbicon/State.hpp @@ -38,7 +38,7 @@ #include -#include "dart/dart.hpp" +#include #define ATLAS_DEFAULT_KD 1.0 // No more than 1.0 #define ATLAS_DEFAULT_KP 1e+3 diff --git a/examples/atlasSimbicon/StateMachine.cpp b/examples/atlasSimbicon/StateMachine.cpp index 281a6173e101..5e9fc3c6cff0 100644 --- a/examples/atlasSimbicon/StateMachine.cpp +++ b/examples/atlasSimbicon/StateMachine.cpp @@ -29,9 +29,9 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/atlasSimbicon/StateMachine.hpp" +#include "StateMachine.hpp" -#include "examples/atlasSimbicon/State.hpp" +#include "State.hpp" // Macro for functions not implemented yet #define NOT_YET(FUNCTION) std::cout << #FUNCTION\ diff --git a/examples/atlasSimbicon/StateMachine.hpp b/examples/atlasSimbicon/StateMachine.hpp index 4dafb1d0018b..7e9f6bfea3f6 100644 --- a/examples/atlasSimbicon/StateMachine.hpp +++ b/examples/atlasSimbicon/StateMachine.hpp @@ -37,7 +37,7 @@ #include -#include "dart/dart.hpp" +#include class State; diff --git a/examples/atlasSimbicon/TerminalCondition.cpp b/examples/atlasSimbicon/TerminalCondition.cpp index cedc26f2df8d..38e84ec489e7 100644 --- a/examples/atlasSimbicon/TerminalCondition.cpp +++ b/examples/atlasSimbicon/TerminalCondition.cpp @@ -29,9 +29,9 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/atlasSimbicon/TerminalCondition.hpp" +#include "TerminalCondition.hpp" -#include "examples/atlasSimbicon/State.hpp" +#include "State.hpp" // Macro for functions not implemented yet #define NOT_YET(FUNCTION) std::cout << #FUNCTION\ diff --git a/examples/atlasSimbicon/TerminalCondition.hpp b/examples/atlasSimbicon/TerminalCondition.hpp index d248dfaac3a8..d9d281a821d1 100644 --- a/examples/atlasSimbicon/TerminalCondition.hpp +++ b/examples/atlasSimbicon/TerminalCondition.hpp @@ -37,7 +37,7 @@ #include -#include "dart/dart.hpp" +#include class State; diff --git a/examples/bipedStand/CMakeLists.txt b/examples/bipedStand/CMakeLists.txt index a8463788049f..d39d3313b827 100644 --- a/examples/bipedStand/CMakeLists.txt +++ b/examples/bipedStand/CMakeLists.txt @@ -1,11 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) + +project(bipedStand) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/bipedStand/Controller.cpp b/examples/bipedStand/Controller.cpp index 4a6b7401e2d7..eedc6e9cee4c 100644 --- a/examples/bipedStand/Controller.cpp +++ b/examples/bipedStand/Controller.cpp @@ -29,7 +29,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/bipedStand/Controller.hpp" +#include "Controller.hpp" Controller::Controller(dart::dynamics::SkeletonPtr _skel, double _t) { diff --git a/examples/bipedStand/Controller.hpp b/examples/bipedStand/Controller.hpp index 1614e4cdc040..1a4fca03a75f 100644 --- a/examples/bipedStand/Controller.hpp +++ b/examples/bipedStand/Controller.hpp @@ -36,7 +36,7 @@ #include -#include "dart/dart.hpp" +#include class Controller { public: diff --git a/examples/bipedStand/Main.cpp b/examples/bipedStand/Main.cpp index 14dd94b951cf..a15b5904f1c4 100644 --- a/examples/bipedStand/Main.cpp +++ b/examples/bipedStand/Main.cpp @@ -32,9 +32,9 @@ #include #include -#include "dart/dart.hpp" +#include -#include "examples/bipedStand/MyWindow.hpp" +#include "MyWindow.hpp" int main(int argc, char* argv[]) { // create and initialize the world diff --git a/examples/bipedStand/MyWindow.cpp b/examples/bipedStand/MyWindow.cpp index 4460df0354da..398a6dd7faf4 100644 --- a/examples/bipedStand/MyWindow.cpp +++ b/examples/bipedStand/MyWindow.cpp @@ -29,7 +29,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/bipedStand/MyWindow.hpp" +#include "MyWindow.hpp" MyWindow::MyWindow(): SimWindow() { mForce = Eigen::Vector3d::Zero(); diff --git a/examples/bipedStand/MyWindow.hpp b/examples/bipedStand/MyWindow.hpp index 3a0ff987d1e9..f59b397daa10 100644 --- a/examples/bipedStand/MyWindow.hpp +++ b/examples/bipedStand/MyWindow.hpp @@ -36,10 +36,10 @@ #include -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include -#include "examples/bipedStand/Controller.hpp" +#include "Controller.hpp" class MyWindow : public dart::gui::SimWindow { public: diff --git a/examples/bipedStand/README b/examples/bipedStand/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/bipedStand/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/hardcodedDesign/CMakeLists.txt b/examples/hardcodedDesign/CMakeLists.txt index a8463788049f..f33ac7c5a699 100644 --- a/examples/hardcodedDesign/CMakeLists.txt +++ b/examples/hardcodedDesign/CMakeLists.txt @@ -1,11 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) + +project(hardcodedDesign) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/hardcodedDesign/Main.cpp b/examples/hardcodedDesign/Main.cpp index d78b1562063e..975b37b99845 100644 --- a/examples/hardcodedDesign/Main.cpp +++ b/examples/hardcodedDesign/Main.cpp @@ -39,9 +39,9 @@ * direction. */ -#include "dart/dart.hpp" +#include -#include "examples/hardcodedDesign/MyWindow.hpp" +#include "MyWindow.hpp" int main(int argc, char* argv[]) { // Create Left Leg skeleton diff --git a/examples/hardcodedDesign/MyWindow.cpp b/examples/hardcodedDesign/MyWindow.cpp index 1d184309c77c..c09bf9b8d01b 100644 --- a/examples/hardcodedDesign/MyWindow.cpp +++ b/examples/hardcodedDesign/MyWindow.cpp @@ -36,7 +36,7 @@ * @brief Simple example of a skeleton created from scratch. */ -#include "examples/hardcodedDesign/MyWindow.hpp" +#include "MyWindow.hpp" void MyWindow::draw() { glDisable(GL_LIGHTING); diff --git a/examples/hardcodedDesign/MyWindow.hpp b/examples/hardcodedDesign/MyWindow.hpp index 9215f985f56b..90578bc06113 100644 --- a/examples/hardcodedDesign/MyWindow.hpp +++ b/examples/hardcodedDesign/MyWindow.hpp @@ -42,8 +42,8 @@ #include #include -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include class MyWindow : public dart::gui::SimWindow { public: diff --git a/examples/hardcodedDesign/README b/examples/hardcodedDesign/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/hardcodedDesign/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/hybridDynamics/CMakeLists.txt b/examples/hybridDynamics/CMakeLists.txt index 4b7d5d9ef980..e911e8eed992 100644 --- a/examples/hybridDynamics/CMakeLists.txt +++ b/examples/hybridDynamics/CMakeLists.txt @@ -1,12 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) +project(hybridDynamics) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/hybridDynamics/Main.cpp b/examples/hybridDynamics/Main.cpp index 0a5541beff67..b24e7b4a9c55 100644 --- a/examples/hybridDynamics/Main.cpp +++ b/examples/hybridDynamics/Main.cpp @@ -30,7 +30,7 @@ */ #include -#include "dart/dart.hpp" +#include #include "MyWindow.hpp" int main(int argc, char* argv[]) @@ -38,7 +38,7 @@ int main(int argc, char* argv[]) // create and initialize the world dart::simulation::WorldPtr myWorld = dart::utils::SkelParser::readWorld( - DART_DATA_PATH"/skel/fullbody1.skel"); + "sample://data/skel/fullbody1.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); myWorld->setGravity(gravity); diff --git a/examples/hybridDynamics/MyWindow.hpp b/examples/hybridDynamics/MyWindow.hpp index 649c6a09de16..0d87aa7ba1b9 100644 --- a/examples/hybridDynamics/MyWindow.hpp +++ b/examples/hybridDynamics/MyWindow.hpp @@ -32,8 +32,8 @@ #ifndef EXAMPLES_HYBRIDDYNAMICS_MYWINDOW_HPP_ #define EXAMPLES_HYBRIDDYNAMICS_MYWINDOW_HPP_ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include /// \brief class MyWindow : public dart::gui::SimWindow diff --git a/examples/hybridDynamics/README b/examples/hybridDynamics/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/hybridDynamics/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/jointConstraints/CMakeLists.txt b/examples/jointConstraints/CMakeLists.txt index 4b7d5d9ef980..40db65bdea17 100644 --- a/examples/jointConstraints/CMakeLists.txt +++ b/examples/jointConstraints/CMakeLists.txt @@ -1,12 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) +project(jointConstraints) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/jointConstraints/Controller.cpp b/examples/jointConstraints/Controller.cpp index ce299ab4f25f..64885e282755 100644 --- a/examples/jointConstraints/Controller.cpp +++ b/examples/jointConstraints/Controller.cpp @@ -29,7 +29,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/jointConstraints/Controller.hpp" +#include "Controller.hpp" using namespace dart; using namespace dynamics; diff --git a/examples/jointConstraints/Controller.hpp b/examples/jointConstraints/Controller.hpp index bbb5ac86ae2c..0b9cc416f0f3 100644 --- a/examples/jointConstraints/Controller.hpp +++ b/examples/jointConstraints/Controller.hpp @@ -36,7 +36,7 @@ #include -#include "dart/dart.hpp" +#include class Controller { diff --git a/examples/jointConstraints/Main.cpp b/examples/jointConstraints/Main.cpp index 87fcdc7baf2a..937392388d6d 100644 --- a/examples/jointConstraints/Main.cpp +++ b/examples/jointConstraints/Main.cpp @@ -29,12 +29,12 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/jointConstraints/MyWindow.hpp" +#include "MyWindow.hpp" #include -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include using namespace dart; using namespace dynamics; diff --git a/examples/jointConstraints/MyWindow.cpp b/examples/jointConstraints/MyWindow.cpp index b47080e7637e..500dc114577f 100644 --- a/examples/jointConstraints/MyWindow.cpp +++ b/examples/jointConstraints/MyWindow.cpp @@ -29,7 +29,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/jointConstraints/MyWindow.hpp" +#include "MyWindow.hpp" using namespace dart; using namespace math; diff --git a/examples/jointConstraints/MyWindow.hpp b/examples/jointConstraints/MyWindow.hpp index e10da98b48bf..b740897037ca 100644 --- a/examples/jointConstraints/MyWindow.hpp +++ b/examples/jointConstraints/MyWindow.hpp @@ -35,10 +35,10 @@ #include #include -#include "examples/jointConstraints/Controller.hpp" +#include "Controller.hpp" -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include class MyWindow : public dart::gui::SimWindow { diff --git a/examples/jointConstraints/README b/examples/jointConstraints/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/jointConstraints/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/mixedChain/CMakeLists.txt b/examples/mixedChain/CMakeLists.txt index 4b7d5d9ef980..58363e21e8d1 100644 --- a/examples/mixedChain/CMakeLists.txt +++ b/examples/mixedChain/CMakeLists.txt @@ -1,12 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) +project(mixedChain) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/mixedChain/Main.cpp b/examples/mixedChain/Main.cpp index 13e39d3b5d1f..7e43a47fa6a9 100644 --- a/examples/mixedChain/Main.cpp +++ b/examples/mixedChain/Main.cpp @@ -37,9 +37,9 @@ #include -#include "dart/dart.hpp" +#include -#include "examples/mixedChain/MyWindow.hpp" +#include "MyWindow.hpp" int main(int argc, char* argv[]) { diff --git a/examples/mixedChain/MyWindow.cpp b/examples/mixedChain/MyWindow.cpp index c1b4f984c335..38ffe6773735 100644 --- a/examples/mixedChain/MyWindow.cpp +++ b/examples/mixedChain/MyWindow.cpp @@ -35,7 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/mixedChain/MyWindow.hpp" +#include "MyWindow.hpp" #define FORCE_ON_RIGIDBODY 500.0; #define FORCE_ON_VERTEX 1.00; diff --git a/examples/mixedChain/MyWindow.hpp b/examples/mixedChain/MyWindow.hpp index 7d373100b1af..df62eef28baa 100644 --- a/examples/mixedChain/MyWindow.hpp +++ b/examples/mixedChain/MyWindow.hpp @@ -38,8 +38,8 @@ #ifndef EXAMPLES_TESTDROP_MYWINDOW_HPP_ #define EXAMPLES_TESTDROP_MYWINDOW_HPP_ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include /// \brief class MyWindow : public dart::gui::SoftSimWindow diff --git a/examples/mixedChain/README b/examples/mixedChain/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/mixedChain/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/operationalSpaceControl/CMakeLists.txt b/examples/operationalSpaceControl/CMakeLists.txt index 303efa5dba70..ac03be5e3313 100644 --- a/examples/operationalSpaceControl/CMakeLists.txt +++ b/examples/operationalSpaceControl/CMakeLists.txt @@ -1,11 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui dart-utils-urdf) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) + +project(operationalSpaceControl) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/operationalSpaceControl/Controller.cpp b/examples/operationalSpaceControl/Controller.cpp index 162b09672d92..89da6454dfe5 100644 --- a/examples/operationalSpaceControl/Controller.cpp +++ b/examples/operationalSpaceControl/Controller.cpp @@ -29,7 +29,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/operationalSpaceControl/Controller.hpp" +#include "Controller.hpp" //============================================================================== Controller::Controller(dart::dynamics::SkeletonPtr _robot, diff --git a/examples/operationalSpaceControl/Controller.hpp b/examples/operationalSpaceControl/Controller.hpp index 5d4590fe94e5..6a5fa95d61e8 100644 --- a/examples/operationalSpaceControl/Controller.hpp +++ b/examples/operationalSpaceControl/Controller.hpp @@ -34,7 +34,7 @@ #include -#include "dart/dart.hpp" +#include /// \brief Operational space controller for 6-dof manipulator class Controller diff --git a/examples/operationalSpaceControl/Main.cpp b/examples/operationalSpaceControl/Main.cpp index d7e315ccc2d8..595f3c972ead 100644 --- a/examples/operationalSpaceControl/Main.cpp +++ b/examples/operationalSpaceControl/Main.cpp @@ -29,9 +29,9 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "dart/dart.hpp" +#include -#include "examples/operationalSpaceControl/MyWindow.hpp" +#include "MyWindow.hpp" int main(int argc, char* argv[]) { diff --git a/examples/operationalSpaceControl/MyWindow.cpp b/examples/operationalSpaceControl/MyWindow.cpp index 03ca4e4b8ed2..7b59258ed53c 100644 --- a/examples/operationalSpaceControl/MyWindow.cpp +++ b/examples/operationalSpaceControl/MyWindow.cpp @@ -29,7 +29,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/operationalSpaceControl/MyWindow.hpp" +#include "MyWindow.hpp" #include diff --git a/examples/operationalSpaceControl/MyWindow.hpp b/examples/operationalSpaceControl/MyWindow.hpp index 4209eed9e6fe..9e11428e20e5 100644 --- a/examples/operationalSpaceControl/MyWindow.hpp +++ b/examples/operationalSpaceControl/MyWindow.hpp @@ -32,8 +32,8 @@ #ifndef EXAMPLES_OPERATIONALSPACECONTROL_MYWINDOW_HPP_ #define EXAMPLES_OPERATIONALSPACECONTROL_MYWINDOW_HPP_ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include #include "Controller.hpp" diff --git a/examples/operationalSpaceControl/README b/examples/operationalSpaceControl/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/operationalSpaceControl/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/osg/CMakeLists.txt b/examples/osg/CMakeLists.txt deleted file mode 100644 index 9dac50aa1d09..000000000000 --- a/examples/osg/CMakeLists.txt +++ /dev/null @@ -1,31 +0,0 @@ -# This directory depends on OpenSceneGraph -if(HAVE_OPENSCENEGRAPH) - -file(GLOB dart_examples_osg_src "*.cpp") -list(SORT dart_examples_osg_src) - -foreach(example ${dart_examples_osg_src}) - get_filename_component(example_base ${example} NAME_WE) - - add_executable(${example_base} ${example}) - target_link_libraries(${example_base} dart dart-gui-osg dart-utils-urdf) - - dart_add_example(${example_base}) -endforeach(example) - -# Automatically identify all subdirectories that should be included in the build system -file(GLOB children RELATIVE ${CMAKE_CURRENT_LIST_DIR} "*") -set(directories "") -foreach(child ${children}) - if(IS_DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/${child}") - if(EXISTS "${CMAKE_CURRENT_LIST_DIR}/${child}/CMakeLists.txt") - list(APPEND directories ${child}) - endif(EXISTS "${CMAKE_CURRENT_LIST_DIR}/${child}/CMakeLists.txt") - endif(IS_DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/${child}") -endforeach(child) - -foreach(EXAMPLE_DIR ${directories}) - add_subdirectory(${EXAMPLE_DIR}) -endforeach(EXAMPLE_DIR) - -endif(HAVE_OPENSCENEGRAPH) diff --git a/examples/osg/osgAtlasSimbicon/CMakeLists.txt b/examples/osg/osgAtlasSimbicon/CMakeLists.txt deleted file mode 100644 index 679ae6cc7973..000000000000 --- a/examples/osg/osgAtlasSimbicon/CMakeLists.txt +++ /dev/null @@ -1,11 +0,0 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui-osg dart-utils-urdf) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/examples/osg/osgTinkertoy/CMakeLists.txt b/examples/osg/osgTinkertoy/CMakeLists.txt deleted file mode 100644 index 679ae6cc7973..000000000000 --- a/examples/osg/osgTinkertoy/CMakeLists.txt +++ /dev/null @@ -1,11 +0,0 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui-osg dart-utils-urdf) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/examples/osgExamples/CMakeLists.txt b/examples/osgExamples/CMakeLists.txt new file mode 100644 index 000000000000..3258de322970 --- /dev/null +++ b/examples/osgExamples/CMakeLists.txt @@ -0,0 +1,23 @@ +# This directory depends on OpenSceneGraph +if(HAVE_OPENSCENEGRAPH) + + # Automatically identify all directories in the examples folder + file(GLOB children RELATIVE ${CMAKE_CURRENT_LIST_DIR} "*") + set(directories "") + foreach(child ${children}) + if(IS_DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/${child}") + + file(GLOB srcs "${CMAKE_CURRENT_LIST_DIR}/${child}/*.cpp") + + if(srcs) + add_executable(${child} ${srcs}) + target_link_libraries(${child} dart dart-utils-urdf dart-gui-osg) + dart_add_example(${child}) + else() + add_subdirectory(${child}) + endif() + + endif() + endforeach() + +endif(HAVE_OPENSCENEGRAPH) diff --git a/examples/osgExamples/osgAtlasPuppet/CMakeLists.txt b/examples/osgExamples/osgAtlasPuppet/CMakeLists.txt new file mode 100644 index 000000000000..a8a6184eb36c --- /dev/null +++ b/examples/osgExamples/osgAtlasPuppet/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(osgAtlasPuppet) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui-osg) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/osgExamples/osgAtlasPuppet/README b/examples/osgExamples/osgAtlasPuppet/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/osgExamples/osgAtlasPuppet/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/osg/osgAtlasPuppet.cpp b/examples/osgExamples/osgAtlasPuppet/osgAtlasPuppet.cpp similarity index 99% rename from examples/osg/osgAtlasPuppet.cpp rename to examples/osgExamples/osgAtlasPuppet/osgAtlasPuppet.cpp index 0f2da6cae69c..5219668e0d83 100644 --- a/examples/osg/osgAtlasPuppet.cpp +++ b/examples/osgExamples/osgAtlasPuppet/osgAtlasPuppet.cpp @@ -511,7 +511,7 @@ SkeletonPtr createAtlas() // Parse in the atlas model DartLoader urdf; SkeletonPtr atlas = - urdf.parseSkeleton(DART_DATA_PATH"sdf/atlas/atlas_v3_no_head.urdf"); + urdf.parseSkeleton("sample://data/sdf/atlas/atlas_v3_no_head.urdf"); // Add a box to the root node to make it easier to click and drag double scale = 0.25; diff --git a/examples/osg/osgAtlasSimbicon/AtlasSimbiconEventHandler.cpp b/examples/osgExamples/osgAtlasSimbicon/AtlasSimbiconEventHandler.cpp similarity index 100% rename from examples/osg/osgAtlasSimbicon/AtlasSimbiconEventHandler.cpp rename to examples/osgExamples/osgAtlasSimbicon/AtlasSimbiconEventHandler.cpp diff --git a/examples/osg/osgAtlasSimbicon/AtlasSimbiconEventHandler.hpp b/examples/osgExamples/osgAtlasSimbicon/AtlasSimbiconEventHandler.hpp similarity index 100% rename from examples/osg/osgAtlasSimbicon/AtlasSimbiconEventHandler.hpp rename to examples/osgExamples/osgAtlasSimbicon/AtlasSimbiconEventHandler.hpp diff --git a/examples/osg/osgAtlasSimbicon/AtlasSimbiconWidget.cpp b/examples/osgExamples/osgAtlasSimbicon/AtlasSimbiconWidget.cpp similarity index 100% rename from examples/osg/osgAtlasSimbicon/AtlasSimbiconWidget.cpp rename to examples/osgExamples/osgAtlasSimbicon/AtlasSimbiconWidget.cpp diff --git a/examples/osg/osgAtlasSimbicon/AtlasSimbiconWidget.hpp b/examples/osgExamples/osgAtlasSimbicon/AtlasSimbiconWidget.hpp similarity index 100% rename from examples/osg/osgAtlasSimbicon/AtlasSimbiconWidget.hpp rename to examples/osgExamples/osgAtlasSimbicon/AtlasSimbiconWidget.hpp diff --git a/examples/osg/osgAtlasSimbicon/AtlasSimbiconWorldNode.cpp b/examples/osgExamples/osgAtlasSimbicon/AtlasSimbiconWorldNode.cpp similarity index 100% rename from examples/osg/osgAtlasSimbicon/AtlasSimbiconWorldNode.cpp rename to examples/osgExamples/osgAtlasSimbicon/AtlasSimbiconWorldNode.cpp diff --git a/examples/osg/osgAtlasSimbicon/AtlasSimbiconWorldNode.hpp b/examples/osgExamples/osgAtlasSimbicon/AtlasSimbiconWorldNode.hpp similarity index 100% rename from examples/osg/osgAtlasSimbicon/AtlasSimbiconWorldNode.hpp rename to examples/osgExamples/osgAtlasSimbicon/AtlasSimbiconWorldNode.hpp diff --git a/examples/osgExamples/osgAtlasSimbicon/CMakeLists.txt b/examples/osgExamples/osgAtlasSimbicon/CMakeLists.txt new file mode 100644 index 000000000000..34da2a9735c1 --- /dev/null +++ b/examples/osgExamples/osgAtlasSimbicon/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(osgAtlasSimbicon) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui-osg) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/osg/osgAtlasSimbicon/Controller.cpp b/examples/osgExamples/osgAtlasSimbicon/Controller.cpp similarity index 100% rename from examples/osg/osgAtlasSimbicon/Controller.cpp rename to examples/osgExamples/osgAtlasSimbicon/Controller.cpp diff --git a/examples/osg/osgAtlasSimbicon/Controller.hpp b/examples/osgExamples/osgAtlasSimbicon/Controller.hpp similarity index 99% rename from examples/osg/osgAtlasSimbicon/Controller.hpp rename to examples/osgExamples/osgAtlasSimbicon/Controller.hpp index 844c052e62da..ab4e75b6b041 100644 --- a/examples/osg/osgAtlasSimbicon/Controller.hpp +++ b/examples/osgExamples/osgAtlasSimbicon/Controller.hpp @@ -36,7 +36,7 @@ #include -#include "dart/dart.hpp" +#include class StateMachine; diff --git a/examples/osgExamples/osgAtlasSimbicon/README b/examples/osgExamples/osgAtlasSimbicon/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/osgExamples/osgAtlasSimbicon/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/osg/osgAtlasSimbicon/State.cpp b/examples/osgExamples/osgAtlasSimbicon/State.cpp similarity index 100% rename from examples/osg/osgAtlasSimbicon/State.cpp rename to examples/osgExamples/osgAtlasSimbicon/State.cpp diff --git a/examples/osg/osgAtlasSimbicon/State.hpp b/examples/osgExamples/osgAtlasSimbicon/State.hpp similarity index 99% rename from examples/osg/osgAtlasSimbicon/State.hpp rename to examples/osgExamples/osgAtlasSimbicon/State.hpp index 8b7fe666f5b0..106ae63245f8 100644 --- a/examples/osg/osgAtlasSimbicon/State.hpp +++ b/examples/osgExamples/osgAtlasSimbicon/State.hpp @@ -38,7 +38,7 @@ #include -#include "dart/dart.hpp" +#include #define ATLAS_DEFAULT_KD 1.0 // No more than 1.0 #define ATLAS_DEFAULT_KP 1e+3 diff --git a/examples/osg/osgAtlasSimbicon/StateMachine.cpp b/examples/osgExamples/osgAtlasSimbicon/StateMachine.cpp similarity index 100% rename from examples/osg/osgAtlasSimbicon/StateMachine.cpp rename to examples/osgExamples/osgAtlasSimbicon/StateMachine.cpp diff --git a/examples/osg/osgAtlasSimbicon/StateMachine.hpp b/examples/osgExamples/osgAtlasSimbicon/StateMachine.hpp similarity index 99% rename from examples/osg/osgAtlasSimbicon/StateMachine.hpp rename to examples/osgExamples/osgAtlasSimbicon/StateMachine.hpp index b7205fb343a3..0c88f33fc905 100644 --- a/examples/osg/osgAtlasSimbicon/StateMachine.hpp +++ b/examples/osgExamples/osgAtlasSimbicon/StateMachine.hpp @@ -37,7 +37,7 @@ #include -#include "dart/dart.hpp" +#include class State; diff --git a/examples/osg/osgAtlasSimbicon/TerminalCondition.cpp b/examples/osgExamples/osgAtlasSimbicon/TerminalCondition.cpp similarity index 100% rename from examples/osg/osgAtlasSimbicon/TerminalCondition.cpp rename to examples/osgExamples/osgAtlasSimbicon/TerminalCondition.cpp diff --git a/examples/osg/osgAtlasSimbicon/TerminalCondition.hpp b/examples/osgExamples/osgAtlasSimbicon/TerminalCondition.hpp similarity index 99% rename from examples/osg/osgAtlasSimbicon/TerminalCondition.hpp rename to examples/osgExamples/osgAtlasSimbicon/TerminalCondition.hpp index d248dfaac3a8..d9d281a821d1 100644 --- a/examples/osg/osgAtlasSimbicon/TerminalCondition.hpp +++ b/examples/osgExamples/osgAtlasSimbicon/TerminalCondition.hpp @@ -37,7 +37,7 @@ #include -#include "dart/dart.hpp" +#include class State; diff --git a/examples/osg/osgAtlasSimbicon/main.cpp b/examples/osgExamples/osgAtlasSimbicon/main.cpp similarity index 96% rename from examples/osg/osgAtlasSimbicon/main.cpp rename to examples/osgExamples/osgAtlasSimbicon/main.cpp index a1ad5c48dd0e..7521e7281ce8 100644 --- a/examples/osg/osgAtlasSimbicon/main.cpp +++ b/examples/osgExamples/osgAtlasSimbicon/main.cpp @@ -44,9 +44,9 @@ int main() // Load ground and Atlas robot and add them to the world dart::utils::DartLoader urdfLoader; - auto ground = urdfLoader.parseSkeleton(DART_DATA_PATH"sdf/atlas/ground.urdf"); + auto ground = urdfLoader.parseSkeleton("sample://data/sdf/atlas/ground.urdf"); auto atlas = dart::utils::SdfParser::readSkeleton( - DART_DATA_PATH"sdf/atlas/atlas_v3_no_head.sdf"); + "sample://data/sdf/atlas/atlas_v3_no_head.sdf"); world->addSkeleton(ground); world->addSkeleton(atlas); diff --git a/examples/osgExamples/osgDragAndDrop/CMakeLists.txt b/examples/osgExamples/osgDragAndDrop/CMakeLists.txt new file mode 100644 index 000000000000..c6f04ecc8124 --- /dev/null +++ b/examples/osgExamples/osgDragAndDrop/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(osgDragAndDrop) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui-osg) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/osgExamples/osgDragAndDrop/README b/examples/osgExamples/osgDragAndDrop/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/osgExamples/osgDragAndDrop/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/osg/osgDragAndDrop.cpp b/examples/osgExamples/osgDragAndDrop/osgDragAndDrop.cpp similarity index 100% rename from examples/osg/osgDragAndDrop.cpp rename to examples/osgExamples/osgDragAndDrop/osgDragAndDrop.cpp diff --git a/examples/osgExamples/osgEmpty/CMakeLists.txt b/examples/osgExamples/osgEmpty/CMakeLists.txt new file mode 100644 index 000000000000..c7e14f43b091 --- /dev/null +++ b/examples/osgExamples/osgEmpty/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(osgEmpty) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui-osg) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/osgExamples/osgEmpty/README b/examples/osgExamples/osgEmpty/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/osgExamples/osgEmpty/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/osg/osgEmpty.cpp b/examples/osgExamples/osgEmpty/osgEmpty.cpp similarity index 100% rename from examples/osg/osgEmpty.cpp rename to examples/osgExamples/osgEmpty/osgEmpty.cpp diff --git a/examples/osgExamples/osgHubuPuppet/CMakeLists.txt b/examples/osgExamples/osgHubuPuppet/CMakeLists.txt new file mode 100644 index 000000000000..e10c789e75c0 --- /dev/null +++ b/examples/osgExamples/osgHubuPuppet/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(osgHubuPuppet) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui-osg) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/osgExamples/osgHubuPuppet/README b/examples/osgExamples/osgHubuPuppet/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/osgExamples/osgHubuPuppet/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/osg/osgHuboPuppet.cpp b/examples/osgExamples/osgHubuPuppet/osgHuboPuppet.cpp similarity index 100% rename from examples/osg/osgHuboPuppet.cpp rename to examples/osgExamples/osgHubuPuppet/osgHuboPuppet.cpp diff --git a/examples/osgExamples/osgImGui/CMakeLists.txt b/examples/osgExamples/osgImGui/CMakeLists.txt new file mode 100644 index 000000000000..6c3f6b6cf28e --- /dev/null +++ b/examples/osgExamples/osgImGui/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(osgImGui) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui-osg) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/osgExamples/osgImGui/README b/examples/osgExamples/osgImGui/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/osgExamples/osgImGui/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/osg/osgImGui.cpp b/examples/osgExamples/osgImGui/osgImGui.cpp similarity index 100% rename from examples/osg/osgImGui.cpp rename to examples/osgExamples/osgImGui/osgImGui.cpp diff --git a/examples/osgExamples/osgOperationalSpaceControl/CMakeLists.txt b/examples/osgExamples/osgOperationalSpaceControl/CMakeLists.txt new file mode 100644 index 000000000000..94834fe54696 --- /dev/null +++ b/examples/osgExamples/osgOperationalSpaceControl/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(osgOperationalSpaceControl) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui-osg) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/osgExamples/osgOperationalSpaceControl/README b/examples/osgExamples/osgOperationalSpaceControl/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/osgExamples/osgOperationalSpaceControl/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/osg/osgOperationalSpaceControl.cpp b/examples/osgExamples/osgOperationalSpaceControl/osgOperationalSpaceControl.cpp similarity index 100% rename from examples/osg/osgOperationalSpaceControl.cpp rename to examples/osgExamples/osgOperationalSpaceControl/osgOperationalSpaceControl.cpp diff --git a/examples/osgExamples/osgSoftBodies/CMakeLists.txt b/examples/osgExamples/osgSoftBodies/CMakeLists.txt new file mode 100644 index 000000000000..851fabf88967 --- /dev/null +++ b/examples/osgExamples/osgSoftBodies/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(osgSoftBodies) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui-osg) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/osgExamples/osgSoftBodies/README b/examples/osgExamples/osgSoftBodies/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/osgExamples/osgSoftBodies/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/osg/osgSoftBodies.cpp b/examples/osgExamples/osgSoftBodies/osgSoftBodies.cpp similarity index 100% rename from examples/osg/osgSoftBodies.cpp rename to examples/osgExamples/osgSoftBodies/osgSoftBodies.cpp diff --git a/examples/osgExamples/osgTinkertoy/CMakeLists.txt b/examples/osgExamples/osgTinkertoy/CMakeLists.txt new file mode 100644 index 000000000000..05aec10bb9c8 --- /dev/null +++ b/examples/osgExamples/osgTinkertoy/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(osgTinkertoy) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui-osg) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/osgExamples/osgTinkertoy/README b/examples/osgExamples/osgTinkertoy/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/osgExamples/osgTinkertoy/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/osg/osgTinkertoy/TinkertoyWidget.cpp b/examples/osgExamples/osgTinkertoy/TinkertoyWidget.cpp similarity index 100% rename from examples/osg/osgTinkertoy/TinkertoyWidget.cpp rename to examples/osgExamples/osgTinkertoy/TinkertoyWidget.cpp diff --git a/examples/osg/osgTinkertoy/TinkertoyWidget.hpp b/examples/osgExamples/osgTinkertoy/TinkertoyWidget.hpp similarity index 100% rename from examples/osg/osgTinkertoy/TinkertoyWidget.hpp rename to examples/osgExamples/osgTinkertoy/TinkertoyWidget.hpp diff --git a/examples/osg/osgTinkertoy/TinkertoyWorldNode.cpp b/examples/osgExamples/osgTinkertoy/TinkertoyWorldNode.cpp similarity index 100% rename from examples/osg/osgTinkertoy/TinkertoyWorldNode.cpp rename to examples/osgExamples/osgTinkertoy/TinkertoyWorldNode.cpp diff --git a/examples/osg/osgTinkertoy/TinkertoyWorldNode.hpp b/examples/osgExamples/osgTinkertoy/TinkertoyWorldNode.hpp similarity index 100% rename from examples/osg/osgTinkertoy/TinkertoyWorldNode.hpp rename to examples/osgExamples/osgTinkertoy/TinkertoyWorldNode.hpp diff --git a/examples/osg/osgTinkertoy/main.cpp b/examples/osgExamples/osgTinkertoy/main.cpp similarity index 100% rename from examples/osg/osgTinkertoy/main.cpp rename to examples/osgExamples/osgTinkertoy/main.cpp diff --git a/examples/rigidChain/CMakeLists.txt b/examples/rigidChain/CMakeLists.txt index a8463788049f..a002efe3072d 100644 --- a/examples/rigidChain/CMakeLists.txt +++ b/examples/rigidChain/CMakeLists.txt @@ -1,11 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) + +project(rigidChain) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/rigidChain/Main.cpp b/examples/rigidChain/Main.cpp index 132dcf787f0b..ea32fbe4a1d9 100644 --- a/examples/rigidChain/Main.cpp +++ b/examples/rigidChain/Main.cpp @@ -29,14 +29,14 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "dart/dart.hpp" +#include -#include "examples/rigidChain/MyWindow.hpp" +#include "MyWindow.hpp" int main(int argc, char* argv[]) { // create and initialize the world dart::simulation::WorldPtr myWorld - = dart::utils::SkelParser::readWorld(DART_DATA_PATH"/skel/chain.skel"); + = dart::utils::SkelParser::readWorld("sample://data/skel/chain.skel"); assert(myWorld != nullptr); // create and initialize the world diff --git a/examples/rigidChain/MyWindow.cpp b/examples/rigidChain/MyWindow.cpp index 2f2d4d4a010a..90bbeb110ee8 100644 --- a/examples/rigidChain/MyWindow.cpp +++ b/examples/rigidChain/MyWindow.cpp @@ -29,7 +29,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/rigidChain/MyWindow.hpp" +#include "MyWindow.hpp" MyWindow::MyWindow() : SimWindow() { } diff --git a/examples/rigidChain/MyWindow.hpp b/examples/rigidChain/MyWindow.hpp index 0b17e3924834..f922b3e8ac15 100644 --- a/examples/rigidChain/MyWindow.hpp +++ b/examples/rigidChain/MyWindow.hpp @@ -32,8 +32,8 @@ #ifndef EXAMPLES_FORWARDSIM_MYWINDOW_HPP_ #define EXAMPLES_FORWARDSIM_MYWINDOW_HPP_ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include class MyWindow : public dart::gui::SimWindow { public: diff --git a/examples/rigidChain/README b/examples/rigidChain/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/rigidChain/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/rigidCubes/CMakeLists.txt b/examples/rigidCubes/CMakeLists.txt index a8463788049f..d89d82ff99ec 100644 --- a/examples/rigidCubes/CMakeLists.txt +++ b/examples/rigidCubes/CMakeLists.txt @@ -1,11 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) + +project(rigidCubes) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/rigidCubes/Main.cpp b/examples/rigidCubes/Main.cpp index 3c8a102f90a4..a5a796257be0 100644 --- a/examples/rigidCubes/Main.cpp +++ b/examples/rigidCubes/Main.cpp @@ -31,14 +31,14 @@ #include -#include "dart/dart.hpp" +#include -#include "examples/rigidCubes/MyWindow.hpp" +#include "MyWindow.hpp" int main(int argc, char* argv[]) { // create and initialize the world dart::simulation::WorldPtr myWorld - = dart::utils::SkelParser::readWorld(DART_DATA_PATH"/skel/cubes.skel"); + = dart::utils::SkelParser::readWorld("sample://data/skel/cubes.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); myWorld->setGravity(gravity); diff --git a/examples/rigidCubes/MyWindow.cpp b/examples/rigidCubes/MyWindow.cpp index 57b1df40f153..1e067eb4d274 100644 --- a/examples/rigidCubes/MyWindow.cpp +++ b/examples/rigidCubes/MyWindow.cpp @@ -29,7 +29,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/rigidCubes/MyWindow.hpp" +#include "MyWindow.hpp" MyWindow::MyWindow() : SimWindow() { diff --git a/examples/rigidCubes/MyWindow.hpp b/examples/rigidCubes/MyWindow.hpp index fcfef2b0b64c..25b1df2c1877 100644 --- a/examples/rigidCubes/MyWindow.hpp +++ b/examples/rigidCubes/MyWindow.hpp @@ -32,8 +32,8 @@ #ifndef EXAMPLES_CUBES_MYWINDOW_HPP_ #define EXAMPLES_CUBES_MYWINDOW_HPP_ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include /// \brief class MyWindow : public dart::gui::SimWindow { diff --git a/examples/rigidCubes/README b/examples/rigidCubes/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/rigidCubes/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/rigidLoop/CMakeLists.txt b/examples/rigidLoop/CMakeLists.txt index a8463788049f..e6ff9a33e23c 100644 --- a/examples/rigidLoop/CMakeLists.txt +++ b/examples/rigidLoop/CMakeLists.txt @@ -1,11 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) + +project(rigidLoop) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/rigidLoop/Main.cpp b/examples/rigidLoop/Main.cpp index bc0ef6683a13..09f86916fdf1 100644 --- a/examples/rigidLoop/Main.cpp +++ b/examples/rigidLoop/Main.cpp @@ -29,9 +29,9 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "dart/dart.hpp" +#include -#include "examples/rigidLoop/MyWindow.hpp" +#include "MyWindow.hpp" using namespace dart; using namespace math; @@ -44,7 +44,7 @@ int main(int argc, char* argv[]) // load a skeleton file // create and initialize the world dart::simulation::WorldPtr myWorld - = utils::SkelParser::readWorld(DART_DATA_PATH"/skel/chain.skel"); + = utils::SkelParser::readWorld("sample://data/skel/chain.skel"); assert(myWorld != nullptr); // create and initialize the world diff --git a/examples/rigidLoop/MyWindow.cpp b/examples/rigidLoop/MyWindow.cpp index 339cd6c8e630..54f67a7c3db3 100644 --- a/examples/rigidLoop/MyWindow.cpp +++ b/examples/rigidLoop/MyWindow.cpp @@ -29,7 +29,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/rigidLoop/MyWindow.hpp" +#include "MyWindow.hpp" void MyWindow::timeStepping() { diff --git a/examples/rigidLoop/MyWindow.hpp b/examples/rigidLoop/MyWindow.hpp index 79a04cf9eeae..80c5c9affa3e 100644 --- a/examples/rigidLoop/MyWindow.hpp +++ b/examples/rigidLoop/MyWindow.hpp @@ -32,8 +32,8 @@ #ifndef EXAMPLES_CLOSEDLOOP_MYWINDOW_HPP_ #define EXAMPLES_CLOSEDLOOP_MYWINDOW_HPP_ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include class MyWindow : public dart::gui::SimWindow { diff --git a/examples/rigidLoop/README b/examples/rigidLoop/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/rigidLoop/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/rigidShapes/CMakeLists.txt b/examples/rigidShapes/CMakeLists.txt index a8463788049f..716c0a25a9f6 100644 --- a/examples/rigidShapes/CMakeLists.txt +++ b/examples/rigidShapes/CMakeLists.txt @@ -1,11 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) + +project(rigidShapes) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/rigidShapes/Main.cpp b/examples/rigidShapes/Main.cpp index 39f26ac18e85..809b1a231138 100644 --- a/examples/rigidShapes/Main.cpp +++ b/examples/rigidShapes/Main.cpp @@ -36,7 +36,7 @@ */ #include -#include "dart/dart.hpp" +#include #include "MyWindow.hpp" #include diff --git a/examples/rigidShapes/MyWindow.hpp b/examples/rigidShapes/MyWindow.hpp index 538c6bcfd987..0d40bfaf2ecc 100644 --- a/examples/rigidShapes/MyWindow.hpp +++ b/examples/rigidShapes/MyWindow.hpp @@ -38,8 +38,8 @@ #ifndef EXAMPLES_RIGIDSHAPES_MYWINDOW_HPP_ #define EXAMPLES_RIGIDSHAPES_MYWINDOW_HPP_ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include /// MyWindow class MyWindow : public dart::gui::SimWindow diff --git a/examples/rigidShapes/README b/examples/rigidShapes/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/rigidShapes/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/simpleFrames/CMakeLists.txt b/examples/simpleFrames/CMakeLists.txt index a8463788049f..c5d2259ca9ed 100644 --- a/examples/simpleFrames/CMakeLists.txt +++ b/examples/simpleFrames/CMakeLists.txt @@ -1,11 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) + +project(simpleFrames) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/simpleFrames/Main.cpp b/examples/simpleFrames/Main.cpp index 1027a1225d64..cf93ad335367 100644 --- a/examples/simpleFrames/Main.cpp +++ b/examples/simpleFrames/Main.cpp @@ -29,8 +29,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include using namespace dart::dynamics; diff --git a/examples/simpleFrames/README b/examples/simpleFrames/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/simpleFrames/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/softBodies/CMakeLists.txt b/examples/softBodies/CMakeLists.txt index a8463788049f..1a4affb2c3ad 100644 --- a/examples/softBodies/CMakeLists.txt +++ b/examples/softBodies/CMakeLists.txt @@ -1,11 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) + +project(softBodies) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/softBodies/Main.cpp b/examples/softBodies/Main.cpp index ceaee470f450..d2f334b9aa3b 100644 --- a/examples/softBodies/Main.cpp +++ b/examples/softBodies/Main.cpp @@ -37,9 +37,9 @@ #include -#include "dart/dart.hpp" +#include -#include "examples/softBodies/MyWindow.hpp" +#include "MyWindow.hpp" int main(int argc, char* argv[]) { diff --git a/examples/softBodies/MyWindow.cpp b/examples/softBodies/MyWindow.cpp index 3ae60c21c73e..d16c880b2604 100644 --- a/examples/softBodies/MyWindow.cpp +++ b/examples/softBodies/MyWindow.cpp @@ -35,7 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/softBodies/MyWindow.hpp" +#include "MyWindow.hpp" #define FORCE_ON_RIGIDBODY 25.0; #define FORCE_ON_VERTEX 1.00; diff --git a/examples/softBodies/MyWindow.hpp b/examples/softBodies/MyWindow.hpp index 377123a2fe6b..bd116b5e53db 100644 --- a/examples/softBodies/MyWindow.hpp +++ b/examples/softBodies/MyWindow.hpp @@ -38,8 +38,8 @@ #ifndef EXAMPLES_SOFTBODIES_MYWINDOW_HPP_ #define EXAMPLES_SOFTBODIES_MYWINDOW_HPP_ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include /// \brief class MyWindow : public dart::gui::SoftSimWindow diff --git a/examples/softBodies/README b/examples/softBodies/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/softBodies/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/speedTest/CMakeLists.txt b/examples/speedTest/CMakeLists.txt index a63994c5ac6e..b766b771ed39 100644 --- a/examples/speedTest/CMakeLists.txt +++ b/examples/speedTest/CMakeLists.txt @@ -1,11 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-utils) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) + +project(speedTest) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/speedTest/Main.cpp b/examples/speedTest/Main.cpp index a87164046543..7dd862703d0a 100644 --- a/examples/speedTest/Main.cpp +++ b/examples/speedTest/Main.cpp @@ -32,7 +32,7 @@ #include #include -#include "dart/dart.hpp" +#include #include "dart/utils/utils.hpp" double testForwardKinematicSpeed(dart::dynamics::SkeletonPtr skel, diff --git a/examples/speedTest/README b/examples/speedTest/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/speedTest/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/examples/vehicle/CMakeLists.txt b/examples/vehicle/CMakeLists.txt index a8463788049f..acd0dae1c8bf 100644 --- a/examples/vehicle/CMakeLists.txt +++ b/examples/vehicle/CMakeLists.txt @@ -1,11 +1,14 @@ -############################################################### -# This file can be used as-is in the directory of any example,# -# however you might need to specify your own dependencies in # -# target_link_libraries if your app depends on more than dart # -############################################################### -get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${example_name}_srcs "*.cpp" "*.hpp") -add_executable(${example_name} ${${example_name}_srcs}) -dart_add_example(${example_name}) -target_link_libraries(${example_name} dart dart-gui) -set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +cmake_minimum_required(VERSION 2.8.12) + +project(vehicle) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) diff --git a/examples/vehicle/Main.cpp b/examples/vehicle/Main.cpp index 40323c42199b..5a36db720861 100644 --- a/examples/vehicle/Main.cpp +++ b/examples/vehicle/Main.cpp @@ -31,9 +31,9 @@ #include -#include "dart/dart.hpp" +#include -#include "examples/vehicle/MyWindow.hpp" +#include "MyWindow.hpp" int main(int argc, char* argv[]) { @@ -43,7 +43,7 @@ int main(int argc, char* argv[]) using namespace utils; // create and initialize the world - WorldPtr myWorld = SkelParser::readWorld(DART_DATA_PATH"/skel/vehicle.skel"); + WorldPtr myWorld = SkelParser::readWorld("sample://data/skel/vehicle.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); myWorld->setGravity(gravity); diff --git a/examples/vehicle/MyWindow.cpp b/examples/vehicle/MyWindow.cpp index 6f052894dbc6..3d23256921d9 100644 --- a/examples/vehicle/MyWindow.cpp +++ b/examples/vehicle/MyWindow.cpp @@ -29,7 +29,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "examples/vehicle/MyWindow.hpp" +#include "MyWindow.hpp" MyWindow::MyWindow() : SimWindow() { diff --git a/examples/vehicle/MyWindow.hpp b/examples/vehicle/MyWindow.hpp index 8c459a8ddf24..e5cfb699b4c9 100644 --- a/examples/vehicle/MyWindow.hpp +++ b/examples/vehicle/MyWindow.hpp @@ -33,8 +33,8 @@ #ifndef EXAMPLES_VEHICLE_MYWINDOW_HPP_ #define EXAMPLES_VEHICLE_MYWINDOW_HPP_ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include /// \brief class MyWindow : public dart::gui::SimWindow { diff --git a/examples/vehicle/README b/examples/vehicle/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/examples/vehicle/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/tutorials/CMakeLists.txt b/tutorials/CMakeLists.txt index 9b9cebdc4f4d..24507e289050 100644 --- a/tutorials/CMakeLists.txt +++ b/tutorials/CMakeLists.txt @@ -1,11 +1,21 @@ -file(GLOB tutorials_src "*.cpp") -list(SORT tutorials_src) +# A list of tutorials +set_property(DIRECTORY PROPERTY FOLDER Tutorials) -foreach(tutorial ${tutorials_src}) - get_filename_component(tutorial_base ${tutorial} NAME_WE) +# Automatically identify all directories in the tutorials folder +file(GLOB children RELATIVE ${CMAKE_CURRENT_LIST_DIR} "*") +set(directories "") +foreach(child ${children}) + if(IS_DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/${child}") - add_executable(${tutorial_base} ${tutorial}) - target_link_libraries(${tutorial_base} dart dart-gui dart-utils-urdf) + file(GLOB srcs "${CMAKE_CURRENT_LIST_DIR}/${child}/*.cpp") - dart_add_tutorial(${tutorial_base}) -endforeach(tutorial) + if(srcs) + add_executable(${child} ${srcs}) + target_link_libraries(${child} dart dart-utils-urdf dart-gui) + dart_add_tutorial(${child}) + else() + add_subdirectory(${child}) + endif() + + endif() +endforeach() diff --git a/tutorials/tutorialBiped-Finished/CMakeLists.txt b/tutorials/tutorialBiped-Finished/CMakeLists.txt new file mode 100644 index 000000000000..4f5dde7463af --- /dev/null +++ b/tutorials/tutorialBiped-Finished/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(tutorialBiped-Finished) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) + diff --git a/tutorials/tutorialBiped-Finished/README b/tutorials/tutorialBiped-Finished/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/tutorials/tutorialBiped-Finished/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/tutorials/tutorialBiped-Finished.cpp b/tutorials/tutorialBiped-Finished/tutorialBiped-Finished.cpp similarity index 99% rename from tutorials/tutorialBiped-Finished.cpp rename to tutorials/tutorialBiped-Finished/tutorialBiped-Finished.cpp index d8b498e9af71..d6aea3408158 100644 --- a/tutorials/tutorialBiped-Finished.cpp +++ b/tutorials/tutorialBiped-Finished/tutorialBiped-Finished.cpp @@ -29,8 +29,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include #if HAVE_BULLET_COLLISION #include "dart/collision/bullet/bullet.hpp" #endif diff --git a/tutorials/tutorialBiped/CMakeLists.txt b/tutorials/tutorialBiped/CMakeLists.txt new file mode 100644 index 000000000000..61746fcd59a8 --- /dev/null +++ b/tutorials/tutorialBiped/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(tutorialBiped) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) + diff --git a/tutorials/tutorialBiped/README b/tutorials/tutorialBiped/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/tutorials/tutorialBiped/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/tutorials/tutorialBiped.cpp b/tutorials/tutorialBiped/tutorialBiped.cpp similarity index 99% rename from tutorials/tutorialBiped.cpp rename to tutorials/tutorialBiped/tutorialBiped.cpp index c01df6136e53..28c362f2fe21 100644 --- a/tutorials/tutorialBiped.cpp +++ b/tutorials/tutorialBiped/tutorialBiped.cpp @@ -29,8 +29,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include #if HAVE_BULLET_COLLISION #include "dart/collision/bullet/bullet.hpp" #endif diff --git a/tutorials/tutorialCollisions-Finished/CMakeLists.txt b/tutorials/tutorialCollisions-Finished/CMakeLists.txt new file mode 100644 index 000000000000..6b64a565c12d --- /dev/null +++ b/tutorials/tutorialCollisions-Finished/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(tutorialCollisions-Finished) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) + diff --git a/tutorials/tutorialCollisions-Finished/README b/tutorials/tutorialCollisions-Finished/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/tutorials/tutorialCollisions-Finished/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/tutorials/tutorialCollisions-Finished.cpp b/tutorials/tutorialCollisions-Finished/tutorialCollisions-Finished.cpp similarity index 99% rename from tutorials/tutorialCollisions-Finished.cpp rename to tutorials/tutorialCollisions-Finished/tutorialCollisions-Finished.cpp index 250ef0899d7a..f8b3dbd6fe16 100644 --- a/tutorials/tutorialCollisions-Finished.cpp +++ b/tutorials/tutorialCollisions-Finished/tutorialCollisions-Finished.cpp @@ -31,8 +31,8 @@ #include -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include const double default_shape_density = 1000; // kg/m^3 const double default_shape_height = 0.1; // m diff --git a/tutorials/tutorialCollisions/CMakeLists.txt b/tutorials/tutorialCollisions/CMakeLists.txt new file mode 100644 index 000000000000..e587d1edd2a4 --- /dev/null +++ b/tutorials/tutorialCollisions/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(tutorialCollisions) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) + diff --git a/tutorials/tutorialCollisions/README b/tutorials/tutorialCollisions/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/tutorials/tutorialCollisions/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/tutorials/tutorialCollisions.cpp b/tutorials/tutorialCollisions/tutorialCollisions.cpp similarity index 99% rename from tutorials/tutorialCollisions.cpp rename to tutorials/tutorialCollisions/tutorialCollisions.cpp index b779b4113b1b..64a303e807d1 100644 --- a/tutorials/tutorialCollisions.cpp +++ b/tutorials/tutorialCollisions/tutorialCollisions.cpp @@ -31,8 +31,8 @@ #include -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include const double default_shape_density = 1000; // kg/m^3 const double default_shape_height = 0.1; // m diff --git a/tutorials/tutorialDominoes-Finished/CMakeLists.txt b/tutorials/tutorialDominoes-Finished/CMakeLists.txt new file mode 100644 index 000000000000..dabb19451919 --- /dev/null +++ b/tutorials/tutorialDominoes-Finished/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(tutorialDominoes-Finished) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) + diff --git a/tutorials/tutorialDominoes-Finished/README b/tutorials/tutorialDominoes-Finished/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/tutorials/tutorialDominoes-Finished/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/tutorials/tutorialDominoes-Finished.cpp b/tutorials/tutorialDominoes-Finished/tutorialDominoes-Finished.cpp similarity index 99% rename from tutorials/tutorialDominoes-Finished.cpp rename to tutorials/tutorialDominoes-Finished/tutorialDominoes-Finished.cpp index 1143655f92cb..59a2bf7980cd 100644 --- a/tutorials/tutorialDominoes-Finished.cpp +++ b/tutorials/tutorialDominoes-Finished/tutorialDominoes-Finished.cpp @@ -29,8 +29,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include const double default_domino_height = 0.3; const double default_domino_width = 0.4 * default_domino_height; diff --git a/tutorials/tutorialDominoes/CMakeLists.txt b/tutorials/tutorialDominoes/CMakeLists.txt new file mode 100644 index 000000000000..26efd73c9e74 --- /dev/null +++ b/tutorials/tutorialDominoes/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(tutorialDominoes) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) + diff --git a/tutorials/tutorialDominoes/README b/tutorials/tutorialDominoes/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/tutorials/tutorialDominoes/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/tutorials/tutorialDominoes.cpp b/tutorials/tutorialDominoes/tutorialDominoes.cpp similarity index 99% rename from tutorials/tutorialDominoes.cpp rename to tutorials/tutorialDominoes/tutorialDominoes.cpp index f8d5360a27bd..a171e95ab367 100644 --- a/tutorials/tutorialDominoes.cpp +++ b/tutorials/tutorialDominoes/tutorialDominoes.cpp @@ -29,8 +29,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include const double default_domino_height = 0.3; const double default_domino_width = 0.4 * default_domino_height; diff --git a/tutorials/tutorialMultiPendulum-Finished/CMakeLists.txt b/tutorials/tutorialMultiPendulum-Finished/CMakeLists.txt new file mode 100644 index 000000000000..55c03dc5dded --- /dev/null +++ b/tutorials/tutorialMultiPendulum-Finished/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(tutorialMultiPendulum-Finished) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) + diff --git a/tutorials/tutorialMultiPendulum-Finished/README b/tutorials/tutorialMultiPendulum-Finished/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/tutorials/tutorialMultiPendulum-Finished/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/tutorials/tutorialMultiPendulum-Finished.cpp b/tutorials/tutorialMultiPendulum-Finished/tutorialMultiPendulum-Finished.cpp similarity index 99% rename from tutorials/tutorialMultiPendulum-Finished.cpp rename to tutorials/tutorialMultiPendulum-Finished/tutorialMultiPendulum-Finished.cpp index eca8db8d9cf1..82b838646c4b 100644 --- a/tutorials/tutorialMultiPendulum-Finished.cpp +++ b/tutorials/tutorialMultiPendulum-Finished/tutorialMultiPendulum-Finished.cpp @@ -29,8 +29,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include const double default_height = 1.0; // m const double default_width = 0.2; // m diff --git a/tutorials/tutorialMultiPendulum/CMakeLists.txt b/tutorials/tutorialMultiPendulum/CMakeLists.txt new file mode 100644 index 000000000000..39e654db632f --- /dev/null +++ b/tutorials/tutorialMultiPendulum/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8.12) + +project(tutorialMultiPendulum) + +find_package(DART 6.1.1 REQUIRED COMPONENTS utils-urdf gui) + +add_compile_options(-std=c++11) + +include_directories(${DART_INCLUDE_DIRS}) + +file(GLOB srcs "*.cpp" "*.hpp") +add_executable(${PROJECT_NAME} ${srcs}) + +target_link_libraries(${PROJECT_NAME} ${DART_LIBRARIES}) + diff --git a/tutorials/tutorialMultiPendulum/README b/tutorials/tutorialMultiPendulum/README new file mode 100644 index 000000000000..1e30c89e5fcc --- /dev/null +++ b/tutorials/tutorialMultiPendulum/README @@ -0,0 +1,18 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +1. Build Instructions + + * From this directory: + $ mkdir build + $ cd build + $ cmake .. + $ make + +2. Execute Instructions + + * Launch the executable from the build directory above: + $ ./{generated_executable} + + * Follow the instructions detailed in the console. + diff --git a/tutorials/tutorialMultiPendulum.cpp b/tutorials/tutorialMultiPendulum/tutorialMultiPendulum.cpp similarity index 99% rename from tutorials/tutorialMultiPendulum.cpp rename to tutorials/tutorialMultiPendulum/tutorialMultiPendulum.cpp index 7954ae59073c..62f3140d9009 100644 --- a/tutorials/tutorialMultiPendulum.cpp +++ b/tutorials/tutorialMultiPendulum/tutorialMultiPendulum.cpp @@ -29,8 +29,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "dart/dart.hpp" -#include "dart/gui/gui.hpp" +#include +#include const double default_height = 1.0; // m const double default_width = 0.2; // m diff --git a/unittests/comprehensive/test_Collision.cpp b/unittests/comprehensive/test_Collision.cpp index 1080e879d682..e6e5c0ebd8d0 100644 --- a/unittests/comprehensive/test_Collision.cpp +++ b/unittests/comprehensive/test_Collision.cpp @@ -1107,7 +1107,7 @@ TEST_F(COLLISION, CollisionOfPrescribedJoints) // Load world and skeleton WorldPtr world = SkelParser::readWorld( - DART_DATA_PATH"/skel/test/collision_of_prescribed_joints_test.skel"); + "sample://data/skel/test/collision_of_prescribed_joints_test.skel"); world->setTimeStep(timeStep); EXPECT_TRUE(world != nullptr); EXPECT_NEAR(world->getTimeStep(), timeStep, tol); diff --git a/unittests/comprehensive/test_Dynamics.cpp b/unittests/comprehensive/test_Dynamics.cpp index 3ffe290f7cd1..bb16a047657a 100644 --- a/unittests/comprehensive/test_Dynamics.cpp +++ b/unittests/comprehensive/test_Dynamics.cpp @@ -2034,7 +2034,7 @@ TEST_F(DynamicsTest, HybridDynamics) // Load world and skeleton WorldPtr world = utils::SkelParser::readWorld( - DART_DATA_PATH"/skel/test/hybrid_dynamics_test.skel"); + "sample://data/skel/test/hybrid_dynamics_test.skel"); world->setTimeStep(timeStep); EXPECT_TRUE(world != nullptr); EXPECT_NEAR(world->getTimeStep(), timeStep, tol); diff --git a/unittests/comprehensive/test_Joints.cpp b/unittests/comprehensive/test_Joints.cpp index dee3a8acc155..130dc6df48a5 100644 --- a/unittests/comprehensive/test_Joints.cpp +++ b/unittests/comprehensive/test_Joints.cpp @@ -386,7 +386,7 @@ TEST_F(JOINTS, COMMAND_LIMIT) { simulation::WorldPtr myWorld = utils::SkelParser::readWorld( - DART_DATA_PATH"/skel/test/joint_limit_test.skel"); + "sample://data/skel/test/joint_limit_test.skel"); EXPECT_TRUE(myWorld != nullptr); dynamics::SkeletonPtr pendulum = myWorld->getSkeleton("double_pendulum"); @@ -428,7 +428,7 @@ TEST_F(JOINTS, POSITION_LIMIT) simulation::WorldPtr myWorld = utils::SkelParser::readWorld( - DART_DATA_PATH"/skel/test/joint_limit_test.skel"); + "sample://data/skel/test/joint_limit_test.skel"); EXPECT_TRUE(myWorld != nullptr); myWorld->setGravity(Eigen::Vector3d(0.0, 0.0, 0.0)); @@ -503,7 +503,7 @@ void testJointCoulombFrictionForce(double _timeStep) simulation::WorldPtr myWorld = utils::SkelParser::readWorld( - DART_DATA_PATH"/skel/test/joint_friction_test.skel"); + "sample://data/skel/test/joint_friction_test.skel"); EXPECT_TRUE(myWorld != nullptr); myWorld->setGravity(Eigen::Vector3d(0.0, 0.0, 0.0)); @@ -816,7 +816,7 @@ TEST_F(JOINTS, JOINT_COULOMB_FRICTION_AND_POSITION_LIMIT) simulation::WorldPtr myWorld = utils::SkelParser::readWorld( - DART_DATA_PATH"/skel/test/joint_friction_test.skel"); + "sample://data/skel/test/joint_friction_test.skel"); EXPECT_TRUE(myWorld != nullptr); myWorld->setGravity(Eigen::Vector3d(0.0, 0.0, 0.0)); diff --git a/unittests/unit/test_FileInfoWorld.cpp b/unittests/unit/test_FileInfoWorld.cpp index 663adbba1379..501084fcefa4 100644 --- a/unittests/unit/test_FileInfoWorld.cpp +++ b/unittests/unit/test_FileInfoWorld.cpp @@ -58,7 +58,7 @@ TEST(FileInfoWorld, Basic) FileInfoWorld worldFile; WorldPtr world = SkelParser::readWorld( - DART_DATA_PATH"/skel/test/file_info_world_test.skel"); + "sample://data/skel/test/file_info_world_test.skel"); EXPECT_TRUE(world != nullptr); Recording* recording1 = nullptr; diff --git a/unittests/unit/test_SampleResourceRetriever.cpp b/unittests/unit/test_SampleResourceRetriever.cpp index 5974cf95e518..81d68099c178 100644 --- a/unittests/unit/test_SampleResourceRetriever.cpp +++ b/unittests/unit/test_SampleResourceRetriever.cpp @@ -38,8 +38,8 @@ using namespace dart; TEST(SampleResourceRetriever, SkelFileExists) { auto retriever = utils::SampleResourceRetriever::create(); - EXPECT_TRUE(retriever->exists("example://data/skel/shapes.skel")); - auto sampleData = retriever->retrieve("example://data/skel/shapes.skel"); + EXPECT_TRUE(retriever->exists("sample://data/skel/shapes.skel")); + auto sampleData = retriever->retrieve("sample://data/skel/shapes.skel"); EXPECT_TRUE(sampleData != nullptr); } diff --git a/unittests/unit/test_SdfParser.cpp b/unittests/unit/test_SdfParser.cpp index 03785b4098f6..8d2d64e1d08d 100644 --- a/unittests/unit/test_SdfParser.cpp +++ b/unittests/unit/test_SdfParser.cpp @@ -52,7 +52,7 @@ TEST(SdfParser, SDFSingleBodyWithoutJoint) // Regression test for #444 WorldPtr world = SdfParser::readWorld( - DART_DATA_PATH"/sdf/test/single_bodynode_skeleton.world"); + "sample://data/sdf/test/single_bodynode_skeleton.world"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel = world->getSkeleton(0); @@ -77,12 +77,12 @@ TEST(SdfParser, ParsingSDFFiles) // Create a list of sdf files to test with where the sdf files contains World std::vector worldFiles; - worldFiles.push_back(DART_DATA_PATH"sdf/benchmark.world"); - worldFiles.push_back(DART_DATA_PATH"sdf/double_pendulum.world"); - worldFiles.push_back(DART_DATA_PATH"sdf/double_pendulum_with_base.world"); - worldFiles.push_back(DART_DATA_PATH"sdf/empty.world"); - worldFiles.push_back(DART_DATA_PATH"sdf/ground.world"); - worldFiles.push_back(DART_DATA_PATH"sdf/test/single_bodynode_skeleton.world"); + worldFiles.push_back("sample://data/sdf/benchmark.world"); + worldFiles.push_back("sample://data/sdf/double_pendulum.world"); + worldFiles.push_back("sample://data/sdf/double_pendulum_with_base.world"); + worldFiles.push_back("sample://data/sdf/empty.world"); + worldFiles.push_back("sample://data/sdf/ground.world"); + worldFiles.push_back("sample://data/sdf/test/single_bodynode_skeleton.world"); std::vector worlds; for (const auto& worldFile : worldFiles) @@ -99,8 +99,8 @@ TEST(SdfParser, ParsingSDFFiles) // Create another list of sdf files to test with where the sdf files contains // Skeleton std::vector skeletonFiles; - skeletonFiles.push_back(DART_DATA_PATH"sdf/atlas/atlas_v3_no_head.sdf"); - skeletonFiles.push_back(DART_DATA_PATH"sdf/atlas/atlas_v3_no_head_soft_feet.sdf"); + skeletonFiles.push_back("sample://data/sdf/atlas/atlas_v3_no_head.sdf"); + skeletonFiles.push_back("sample://data/sdf/atlas/atlas_v3_no_head_soft_feet.sdf"); auto world = std::make_shared(); std::vector skeletons; @@ -122,7 +122,7 @@ TEST(SdfParser, ParsingSDFFiles) //============================================================================== TEST(SdfParser, ReadMaterial) { - std::string sdf_filename = DART_DATA_PATH"sdf/quad.sdf"; + std::string sdf_filename = "sample://data/sdf/quad.sdf"; SkeletonPtr skeleton = SdfParser::readSkeleton(sdf_filename); EXPECT_TRUE(nullptr != skeleton); auto bodynode = skeleton->getBodyNode(0); diff --git a/unittests/unit/test_SkelParser.cpp b/unittests/unit/test_SkelParser.cpp index 8f41fb4b53f4..7302a65157b3 100644 --- a/unittests/unit/test_SkelParser.cpp +++ b/unittests/unit/test_SkelParser.cpp @@ -301,7 +301,7 @@ TEST(SkelParser, PlanarJoint) TEST(SKEL_PARSER, JointActuatorType) { WorldPtr world = SkelParser::readWorld( - DART_DATA_PATH"/skel/test/joint_actuator_type_test.skel"); + "sample://data/skel/test/joint_actuator_type_test.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); @@ -334,7 +334,7 @@ TEST(SKEL_PARSER, JointActuatorType) TEST(SkelParser, DofAttributes) { WorldPtr world = SkelParser::readWorld( - DART_DATA_PATH"/skel/test/dof_attribute_test.skel"); + "sample://data/skel/test/dof_attribute_test.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); @@ -412,7 +412,7 @@ TEST(SkelParser, JointDynamicsElements) { WorldPtr world = SkelParser::readWorld( - DART_DATA_PATH"/skel/test/joint_dynamics_elements_test.skel"); + "sample://data/skel/test/joint_dynamics_elements_test.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); From 95b80d434d219692728a8edc83641e5a80d1b062 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Mon, 30 Jan 2017 21:57:17 -0500 Subject: [PATCH 03/14] Make SdfParser use URI instead of file path for base location --- dart/utils/SampleResourceRetriever.hpp | 2 +- dart/utils/SkelParser.cpp | 24 +++--- dart/utils/SkelParser.hpp | 2 +- dart/utils/sdf/SdfParser.cpp | 109 +++++++++++-------------- dart/utils/sdf/SdfParser.hpp | 6 +- unittests/unit/test_SdfParser.cpp | 2 +- 6 files changed, 66 insertions(+), 79 deletions(-) diff --git a/dart/utils/SampleResourceRetriever.hpp b/dart/utils/SampleResourceRetriever.hpp index edc3ccfe4e45..2f1c74569f63 100644 --- a/dart/utils/SampleResourceRetriever.hpp +++ b/dart/utils/SampleResourceRetriever.hpp @@ -38,7 +38,7 @@ namespace dart { namespace utils { -/// Retrieve resources from sample data URI. +/// Retrieve local resources from sample data URI. /// /// SampleResourceRetriever searches files in the following order: /// 1) DART_DATA_LOCAL_PATH: path to the data directory in source diff --git a/dart/utils/SkelParser.cpp b/dart/utils/SkelParser.cpp index 1c101dce29d7..bb50c057e8da 100644 --- a/dart/utils/SkelParser.cpp +++ b/dart/utils/SkelParser.cpp @@ -423,7 +423,7 @@ simulation::WorldPtr SkelParser::readWorld( return nullptr; } - return ::dart::utils:: readWorld(worldElement, _uri, retriever); + return ::dart::utils::readWorld(worldElement, _uri, retriever); } //============================================================================== @@ -453,21 +453,21 @@ simulation::WorldPtr SkelParser::readWorldXML( //============================================================================== dynamics::SkeletonPtr SkelParser::readSkeleton( - const common::Uri& _fileUri, - const common::ResourceRetrieverPtr& _retriever) + const common::Uri& uri, + const common::ResourceRetrieverPtr& nullOrRetriever) { - const common::ResourceRetrieverPtr retriever = getRetriever(_retriever); + const common::ResourceRetrieverPtr retriever = getRetriever(nullOrRetriever); //-------------------------------------------------------------------------- // Load xml and create Document - tinyxml2::XMLDocument _dartFile; + tinyxml2::XMLDocument dartFile; try { - openXMLFile(_dartFile, _fileUri, retriever); + openXMLFile(dartFile, uri, retriever); } catch(std::exception const& e) { - std::cout << "LoadFile [" << _fileUri.toString() << "] Fails: " + std::cout << "LoadFile [" << uri.toString() << "] Fails: " << e.what() << std::endl; return nullptr; } @@ -475,10 +475,10 @@ dynamics::SkeletonPtr SkelParser::readSkeleton( //-------------------------------------------------------------------------- // Load DART tinyxml2::XMLElement* skelElement = nullptr; - skelElement = _dartFile.FirstChildElement("skel"); + skelElement = dartFile.FirstChildElement("skel"); if (skelElement == nullptr) { - dterr << "Skel file[" << _fileUri.toString() + dterr << "Skel file[" << uri.toString() << "] does not contain as the element.\n"; return nullptr; } @@ -489,14 +489,14 @@ dynamics::SkeletonPtr SkelParser::readSkeleton( skeletonElement = skelElement->FirstChildElement("skeleton"); if (skeletonElement == nullptr) { - dterr << "Skel file[" << _fileUri.toString() + dterr << "Skel file[" << uri.toString() << "] does not contain element " <<"under element.\n"; return nullptr; } dynamics::SkeletonPtr newSkeleton = ::dart::utils:: readSkeleton( - skeletonElement, _fileUri, retriever); + skeletonElement, uri, retriever); return newSkeleton; } @@ -745,7 +745,7 @@ simulation::WorldPtr readWorld( while (SkeletonElements.next()) { dynamics::SkeletonPtr newSkeleton - = ::dart::utils:: readSkeleton(SkeletonElements.get(), _baseUri, _retriever); + = ::dart::utils::readSkeleton(SkeletonElements.get(), _baseUri, _retriever); newWorld->addSkeleton(newSkeleton); } diff --git a/dart/utils/SkelParser.hpp b/dart/utils/SkelParser.hpp index e86468eff92e..dfa162d7d82e 100644 --- a/dart/utils/SkelParser.hpp +++ b/dart/utils/SkelParser.hpp @@ -56,7 +56,7 @@ namespace SkelParser { /// Read Skeleton from skel file dynamics::SkeletonPtr readSkeleton( - const common::Uri& fileUri, + const common::Uri& uri, const common::ResourceRetrieverPtr& retriever = nullptr); } // namespace SkelParser diff --git a/dart/utils/sdf/SdfParser.cpp b/dart/utils/sdf/SdfParser.cpp index c52c7998b402..ffba6c21e8ad 100644 --- a/dart/utils/sdf/SdfParser.cpp +++ b/dart/utils/sdf/SdfParser.cpp @@ -98,17 +98,15 @@ using BodyMap = Eigen::aligned_map; // Maps a child BodyNode to the properties of its parent Joint using JointMap = std::map; -simulation::WorldPtr readWorld( - tinyxml2::XMLElement* worldElement, - const std::string& skelPath, +simulation::WorldPtr readWorld(tinyxml2::XMLElement* worldElement, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever); void readPhysics(tinyxml2::XMLElement* physicsElement, simulation::WorldPtr world); -dynamics::SkeletonPtr readSkeleton( - tinyxml2::XMLElement* skeletonElement, - const std::string& skelPath, +dynamics::SkeletonPtr readSkeleton(tinyxml2::XMLElement* skeletonElement, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever); bool createPair(dynamics::SkeletonPtr skeleton, @@ -145,29 +143,28 @@ std::pair createJointAndNodePair( BodyMap readAllBodyNodes( tinyxml2::XMLElement* skeletonElement, - const std::string& skelPath, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever, const Eigen::Isometry3d& skeletonFrame); SDFBodyNode readBodyNode( tinyxml2::XMLElement* bodyNodeElement, const Eigen::Isometry3d& skeletonFrame, - const std::string& skelPath, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever); dynamics::SoftBodyNode::UniqueProperties readSoftBodyProperties( tinyxml2::XMLElement* softBodyNodeElement); -dynamics::ShapePtr readShape( - tinyxml2::XMLElement* shapelement, - const std::string& skelPath, +dynamics::ShapePtr readShape(tinyxml2::XMLElement* shapelement, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever); dynamics::ShapeNode* readShapeNode( dynamics::BodyNode* bodyNode, tinyxml2::XMLElement* shapeNodeEle, const std::string& shapeNodeName, - const std::string& skelPath, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever); @@ -175,22 +172,19 @@ void readMaterial( tinyxml2::XMLElement* materialEle, dynamics::ShapeNode* shapeNode); -void readVisualizationShapeNode( - dynamics::BodyNode* bodyNode, +void readVisualizationShapeNode(dynamics::BodyNode* bodyNode, tinyxml2::XMLElement* vizShapeNodeEle, - const std::string& skelPath, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever); -void readCollisionShapeNode( - dynamics::BodyNode* bodyNode, +void readCollisionShapeNode(dynamics::BodyNode* bodyNode, tinyxml2::XMLElement* collShapeNodeEle, - const std::string& skelPath, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever); -void readAspects( - const dynamics::SkeletonPtr& skeleton, +void readAspects(const dynamics::SkeletonPtr& skeleton, tinyxml2::XMLElement* skeletonElement, - const std::string& skelPath, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever); JointMap readAllJoints( @@ -242,29 +236,29 @@ common::ResourceRetrieverPtr getRetriever( //============================================================================== simulation::WorldPtr readSdfFile( - const common::Uri& fileUri, + const common::Uri& uri, const common::ResourceRetrieverPtr& nullOrRetriever) { - return readWorld(fileUri, nullOrRetriever); + return readWorld(uri, nullOrRetriever); } //============================================================================== simulation::WorldPtr readWorld( - const common::Uri& fileUri, + const common::Uri& uri, const common::ResourceRetrieverPtr& nullOrRetriever) { const auto retriever = getRetriever(nullOrRetriever); //-------------------------------------------------------------------------- // Load xml and create Document - tinyxml2::XMLDocument _dartFile; + tinyxml2::XMLDocument sdfFile; try { - openXMLFile(_dartFile, fileUri, retriever); + openXMLFile(sdfFile, uri, retriever); } catch(std::exception const& e) { - dtwarn << "[SdfParser::readSdfFile] Loading file [" << fileUri.toString() + dtwarn << "[SdfParser::readSdfFile] Loading file [" << uri.toString() << "] failed: " << e.what() << "\n"; return nullptr; } @@ -272,7 +266,7 @@ simulation::WorldPtr readWorld( //-------------------------------------------------------------------------- // Load DART tinyxml2::XMLElement* sdfElement = nullptr; - sdfElement = _dartFile.FirstChildElement("sdf"); + sdfElement = sdfFile.FirstChildElement("sdf"); if (sdfElement == nullptr) return nullptr; @@ -284,7 +278,7 @@ simulation::WorldPtr readWorld( if (version != "1.4" && version != "1.5") { dtwarn << "[SdfParser::readSdfFile] The file format of [" - << fileUri.toString() + << uri.toString() << "] was found to be [" << version << "], but we only support SDF " << "1.4 and 1.5!\n"; return nullptr; @@ -297,15 +291,12 @@ simulation::WorldPtr readWorld( if (worldElement == nullptr) return nullptr; - std::string fileName = fileUri.getFilesystemPath(); // Uri's path is unix-style path - std::string skelPath = fileName.substr(0, fileName.rfind("/") + 1); - - return readWorld(worldElement, skelPath, retriever); + return readWorld(worldElement, uri, retriever); } //============================================================================== dynamics::SkeletonPtr readSkeleton( - const common::Uri& fileUri, + const common::Uri& uri, const common::ResourceRetrieverPtr& nullOrRetriever) { const auto retriever = getRetriever(nullOrRetriever); @@ -315,11 +306,11 @@ dynamics::SkeletonPtr readSkeleton( tinyxml2::XMLDocument _dartFile; try { - openXMLFile(_dartFile, fileUri, retriever); + openXMLFile(_dartFile, uri, retriever); } catch(std::exception const& e) { - dtwarn << "[SdfParser::readSkeleton] Loading file [" << fileUri.toString() + dtwarn << "[SdfParser::readSkeleton] Loading file [" << uri.toString() << "] failed: " << e.what() << "\n"; return nullptr; } @@ -339,7 +330,7 @@ dynamics::SkeletonPtr readSkeleton( if (version != "1.4" && version != "1.5") { dtwarn << "[SdfParser::readSdfFile] The file format of [" - << fileUri.toString() << "] was found to be [" << version + << uri.toString() << "] was found to be [" << version << "], but we only support SDF 1.4 and 1.5!\n"; return nullptr; } @@ -350,11 +341,7 @@ dynamics::SkeletonPtr readSkeleton( if (skelElement == nullptr) return nullptr; - std::string fileName = fileUri.getFilesystemPath(); // Uri's path is unix-style path - std::string skelPath = fileName.substr(0, fileName.rfind("/") + 1); - - dynamics::SkeletonPtr newSkeleton = readSkeleton(skelElement, skelPath, - retriever); + dynamics::SkeletonPtr newSkeleton = readSkeleton(skelElement, uri, retriever); return newSkeleton; } @@ -367,7 +354,7 @@ namespace { //============================================================================== simulation::WorldPtr readWorld( tinyxml2::XMLElement* worldElement, - const std::string& skelPath, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever) { assert(worldElement != nullptr); @@ -394,7 +381,7 @@ simulation::WorldPtr readWorld( while (skeletonElements.next()) { dynamics::SkeletonPtr newSkeleton - = readSkeleton(skeletonElements.get(), skelPath, retriever); + = readSkeleton(skeletonElements.get(), baseUri, retriever); newWorld->addSkeleton(newSkeleton); } @@ -434,7 +421,7 @@ void readPhysics(tinyxml2::XMLElement* physicsElement, //============================================================================== dynamics::SkeletonPtr readSkeleton( tinyxml2::XMLElement* skeletonElement, - const std::string& skelPath, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever) { assert(skeletonElement != nullptr); @@ -446,7 +433,7 @@ dynamics::SkeletonPtr readSkeleton( //-------------------------------------------------------------------------- // Bodies BodyMap sdfBodyNodes = readAllBodyNodes( - skeletonElement, skelPath, retriever, skeletonFrame); + skeletonElement, baseUri, retriever, skeletonFrame); //-------------------------------------------------------------------------- // Joints @@ -495,7 +482,7 @@ dynamics::SkeletonPtr readSkeleton( // Read aspects here since aspects cannot be added if the BodyNodes haven't // created yet. - readAspects(newSkeleton, skeletonElement, skelPath, retriever); + readAspects(newSkeleton, skeletonElement, baseUri, retriever); // Set positions to their initial values newSkeleton->resetPositions(); @@ -659,7 +646,7 @@ std::pair createJointAndNodePair( //============================================================================== BodyMap readAllBodyNodes( tinyxml2::XMLElement* skeletonElement, - const std::string& skelPath, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever, const Eigen::Isometry3d& skeletonFrame) { @@ -668,7 +655,7 @@ BodyMap readAllBodyNodes( while (bodies.next()) { SDFBodyNode body = readBodyNode( - bodies.get(), skeletonFrame, skelPath, retriever); + bodies.get(), skeletonFrame, baseUri, retriever); BodyMap::iterator it = sdfBodyNodes.find(body.properties->mName); if(it != sdfBodyNodes.end()) @@ -689,7 +676,7 @@ BodyMap readAllBodyNodes( SDFBodyNode readBodyNode( tinyxml2::XMLElement* bodyNodeElement, const Eigen::Isometry3d& skeletonFrame, - const std::string& /*skelPath*/, + const common::Uri& /*baseUri*/, const common::ResourceRetrieverPtr& /*retriever*/) { assert(bodyNodeElement != nullptr); @@ -884,7 +871,7 @@ dynamics::SoftBodyNode::UniqueProperties readSoftBodyProperties( //============================================================================== dynamics::ShapePtr readShape( tinyxml2::XMLElement* _shapelement, - const std::string& _skelPath, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& _retriever) { dynamics::ShapePtr newShape; @@ -947,7 +934,7 @@ dynamics::ShapePtr readShape( Eigen::Vector3d scale = hasElement(meshEle, "scale")? getValueVector3d(meshEle, "scale") : Eigen::Vector3d::Ones(); - const std::string meshUri = common::Uri::getRelativeUri(_skelPath, uri); + const std::string meshUri = common::Uri::getRelativeUri(baseUri, uri); const aiScene* model = dynamics::MeshShape::loadMesh(meshUri, _retriever); if (model) @@ -974,12 +961,12 @@ dynamics::ShapeNode* readShapeNode( dynamics::BodyNode* bodyNode, tinyxml2::XMLElement* shapeNodeEle, const std::string& shapeNodeName, - const std::string& skelPath, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever) { assert(bodyNode); - auto shape = readShape(shapeNodeEle, skelPath, retriever); + auto shape = readShape(shapeNodeEle, baseUri, retriever); auto shapeNode = bodyNode->createShapeNode(shape, shapeNodeName); // Transformation @@ -1020,13 +1007,13 @@ void readMaterial( void readVisualizationShapeNode( dynamics::BodyNode* bodyNode, tinyxml2::XMLElement* vizShapeNodeEle, - const std::string& skelPath, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever) { dynamics::ShapeNode* newShapeNode = readShapeNode(bodyNode, vizShapeNodeEle, bodyNode->getName() + " - visual shape", - skelPath, retriever); + baseUri, retriever); newShapeNode->createVisualAspect(); @@ -1042,13 +1029,13 @@ void readVisualizationShapeNode( void readCollisionShapeNode( dynamics::BodyNode* bodyNode, tinyxml2::XMLElement* collShapeNodeEle, - const std::string& skelPath, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever) { dynamics::ShapeNode* newShapeNode = readShapeNode(bodyNode, collShapeNodeEle, bodyNode->getName() + " - collision shape", - skelPath, retriever); + baseUri, retriever); newShapeNode->createCollisionAspect(); } @@ -1057,7 +1044,7 @@ void readCollisionShapeNode( void readAspects( const dynamics::SkeletonPtr& skeleton, tinyxml2::XMLElement* skeletonElement, - const std::string& skelPath, + const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever) { ElementEnumerator xmlBodies(skeletonElement, "link"); @@ -1071,14 +1058,14 @@ void readAspects( ElementEnumerator vizShapes(bodyElement, "visual"); while (vizShapes.next()) { - readVisualizationShapeNode(bodyNode, vizShapes.get(), skelPath, + readVisualizationShapeNode(bodyNode, vizShapes.get(), baseUri, retriever); } // collision_shape ElementEnumerator collShapes(bodyElement, "collision"); while (collShapes.next()) - readCollisionShapeNode(bodyNode, collShapes.get(), skelPath, retriever); + readCollisionShapeNode(bodyNode, collShapes.get(), baseUri, retriever); } } diff --git a/dart/utils/sdf/SdfParser.hpp b/dart/utils/sdf/SdfParser.hpp index d8c5c7a2e3ab..f2ad1e17062a 100644 --- a/dart/utils/sdf/SdfParser.hpp +++ b/dart/utils/sdf/SdfParser.hpp @@ -44,15 +44,15 @@ namespace SdfParser { DART_DEPRECATED(6.0) simulation::WorldPtr readSdfFile( - const common::Uri& fileUri, + const common::Uri& uri, const common::ResourceRetrieverPtr& retriever = nullptr); simulation::WorldPtr readWorld( - const common::Uri& fileUri, + const common::Uri& uri, const common::ResourceRetrieverPtr& retriever = nullptr); dynamics::SkeletonPtr readSkeleton( - const common::Uri& fileUri, + const common::Uri& uri, const common::ResourceRetrieverPtr& retriever = nullptr); } // namespace SdfParser diff --git a/unittests/unit/test_SdfParser.cpp b/unittests/unit/test_SdfParser.cpp index 8d2d64e1d08d..8676e1b5b3ab 100644 --- a/unittests/unit/test_SdfParser.cpp +++ b/unittests/unit/test_SdfParser.cpp @@ -98,7 +98,7 @@ TEST(SdfParser, ParsingSDFFiles) // Create another list of sdf files to test with where the sdf files contains // Skeleton - std::vector skeletonFiles; + std::vector skeletonFiles; skeletonFiles.push_back("sample://data/sdf/atlas/atlas_v3_no_head.sdf"); skeletonFiles.push_back("sample://data/sdf/atlas/atlas_v3_no_head_soft_feet.sdf"); From 4363ec8556f4a3e89de61bab86eebe6710f1e8a2 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Mon, 30 Jan 2017 22:15:16 -0500 Subject: [PATCH 04/14] Change URI of sample data to "file://sample/..." --- dart/utils/SampleResourceRetriever.cpp | 4 +-- dart/utils/SampleResourceRetriever.hpp | 27 +++++++++++-------- dart/utils/SkelParser.cpp | 2 +- dart/utils/VskParser.cpp | 2 +- dart/utils/sdf/SdfParser.cpp | 2 +- dart/utils/urdf/DartLoader.cpp | 2 +- examples/addDeleteSkels/Main.cpp | 2 +- examples/atlasSimbicon/Main.cpp | 2 +- examples/hybridDynamics/Main.cpp | 2 +- .../osgAtlasPuppet/osgAtlasPuppet.cpp | 2 +- .../osgExamples/osgAtlasSimbicon/main.cpp | 4 +-- examples/rigidChain/Main.cpp | 2 +- examples/rigidCubes/Main.cpp | 2 +- examples/rigidLoop/Main.cpp | 2 +- examples/vehicle/Main.cpp | 2 +- unittests/comprehensive/test_Collision.cpp | 2 +- unittests/comprehensive/test_Dynamics.cpp | 2 +- unittests/comprehensive/test_Joints.cpp | 8 +++--- unittests/unit/test_FileInfoWorld.cpp | 2 +- .../unit/test_SampleResourceRetriever.cpp | 4 +-- unittests/unit/test_SdfParser.cpp | 20 +++++++------- unittests/unit/test_SkelParser.cpp | 6 ++--- 22 files changed, 54 insertions(+), 49 deletions(-) diff --git a/dart/utils/SampleResourceRetriever.cpp b/dart/utils/SampleResourceRetriever.cpp index 7a61a13b17bd..65440c4c267b 100644 --- a/dart/utils/SampleResourceRetriever.cpp +++ b/dart/utils/SampleResourceRetriever.cpp @@ -107,10 +107,10 @@ bool SampleResourceRetriever::resolveDataUri( const common::Uri& uri, std::string& relativePath) const { - if (uri.mScheme.get_value_or("sample") != "sample") + if (uri.mScheme.get_value_or("file") != "file") return false; - if (!uri.mAuthority) + if (uri.mAuthority.get() != "sample") { dtwarn << "[SampleResourceRetriever::resolveDataUri] Invalid URI: The " << "authority of '" << uri.toString() << "' should be 'example'.\n"; diff --git a/dart/utils/SampleResourceRetriever.hpp b/dart/utils/SampleResourceRetriever.hpp index 2f1c74569f63..54ca89ea0664 100644 --- a/dart/utils/SampleResourceRetriever.hpp +++ b/dart/utils/SampleResourceRetriever.hpp @@ -38,23 +38,28 @@ namespace dart { namespace utils { -/// Retrieve local resources from sample data URI. +/// +/// Retrieve local resources from sample data files given file URI. The scheme +/// and authority should be "file" and "sample", respectively. +/// +/// Example of a sample data URI: +/// @code +/// "file://sample/skel/shapes.skel" +/// \______________/ +/// | +/// file path with respect to +/// the sample data directory +/// @endcode /// /// SampleResourceRetriever searches files in the following order: /// 1) DART_DATA_LOCAL_PATH: path to the data directory in source /// (e.g., [DART_SRC_ROOT]/data/). /// 2) DART_DATA_GLOBAL_PATH: path to the data directory installed at a system -/// directory. The location can be varied depending on OS -/// (e.g., Linux: /usr/local/share/doc/dart/data/). +/// directory. The location can be varied depending on OS. +/// (e.g., Linux: /usr/local/share/doc/dart/data/) +/// where DART_DATA_LOCAL_PATH and DART_DATA_GLOBAL_PATH are defined in +/// config.hpp that are determined in CMake time. /// -/// Example of a sample data URI: -/// @code -/// "sample://data/skel/shapes.skel" -/// \______________/ -/// | -/// file path with respect to -/// the data directory -/// @endcode class SampleResourceRetriever : public common::ResourceRetriever { public: diff --git a/dart/utils/SkelParser.cpp b/dart/utils/SkelParser.cpp index bb50c057e8da..e7cf747371cc 100644 --- a/dart/utils/SkelParser.cpp +++ b/dart/utils/SkelParser.cpp @@ -2417,7 +2417,7 @@ common::ResourceRetrieverPtr getRetriever( newRetriever->addSchemaRetriever( "file", std::make_shared()); newRetriever->addSchemaRetriever( - "sample", SampleResourceRetriever::create()); + "file", SampleResourceRetriever::create()); return newRetriever; } diff --git a/dart/utils/VskParser.cpp b/dart/utils/VskParser.cpp index 3c420357b040..b01bb6ab4d52 100644 --- a/dart/utils/VskParser.cpp +++ b/dart/utils/VskParser.cpp @@ -1033,7 +1033,7 @@ common::ResourceRetrieverPtr getRetriever( newRetriever->addSchemaRetriever( "file", std::make_shared()); newRetriever->addSchemaRetriever( - "sample", SampleResourceRetriever::create()); + "file", SampleResourceRetriever::create()); return newRetriever; } diff --git a/dart/utils/sdf/SdfParser.cpp b/dart/utils/sdf/SdfParser.cpp index ffba6c21e8ad..3a6dffdb5be2 100644 --- a/dart/utils/sdf/SdfParser.cpp +++ b/dart/utils/sdf/SdfParser.cpp @@ -1499,7 +1499,7 @@ common::ResourceRetrieverPtr getRetriever( newRetriever->addSchemaRetriever( "file", std::make_shared()); newRetriever->addSchemaRetriever( - "sample", SampleResourceRetriever::create()); + "file", SampleResourceRetriever::create()); return newRetriever; } diff --git a/dart/utils/urdf/DartLoader.cpp b/dart/utils/urdf/DartLoader.cpp index 08e8df3c5b09..b751eeed68df 100644 --- a/dart/utils/urdf/DartLoader.cpp +++ b/dart/utils/urdf/DartLoader.cpp @@ -68,7 +68,7 @@ DartLoader::DartLoader() { mRetriever->addSchemaRetriever("file", mLocalRetriever); mRetriever->addSchemaRetriever("package", mPackageRetriever); - mRetriever->addSchemaRetriever("sample", SampleResourceRetriever::create()); + mRetriever->addSchemaRetriever("file", SampleResourceRetriever::create()); } void DartLoader::addPackageDirectory(const std::string& _packageName, diff --git a/examples/addDeleteSkels/Main.cpp b/examples/addDeleteSkels/Main.cpp index f822aee07ebc..cd89dadf5039 100644 --- a/examples/addDeleteSkels/Main.cpp +++ b/examples/addDeleteSkels/Main.cpp @@ -38,7 +38,7 @@ int main(int argc, char* argv[]) { // create and initialize the world dart::simulation::WorldPtr myWorld - = dart::utils::SkelParser::readWorld("sample://data/skel/ground.skel"); + = dart::utils::SkelParser::readWorld("file://sample/skel/ground.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); myWorld->setGravity(gravity); diff --git a/examples/atlasSimbicon/Main.cpp b/examples/atlasSimbicon/Main.cpp index 9495a1947e66..dffdc840b02c 100644 --- a/examples/atlasSimbicon/Main.cpp +++ b/examples/atlasSimbicon/Main.cpp @@ -52,7 +52,7 @@ int main(int argc, char* argv[]) // Load ground and Atlas robot and add them to the world DartLoader urdfLoader; SkeletonPtr ground = urdfLoader.parseSkeleton( - "sample://data/sdf/atlas/ground.urdf"); + "file://sample/sdf/atlas/ground.urdf"); SkeletonPtr atlas = SdfParser::readSkeleton( DART_DATA_PATH"sdf/atlas/atlas_v3_no_head_soft_feet.sdf"); myWorld->addSkeleton(atlas); diff --git a/examples/hybridDynamics/Main.cpp b/examples/hybridDynamics/Main.cpp index b24e7b4a9c55..5048e42f24d7 100644 --- a/examples/hybridDynamics/Main.cpp +++ b/examples/hybridDynamics/Main.cpp @@ -38,7 +38,7 @@ int main(int argc, char* argv[]) // create and initialize the world dart::simulation::WorldPtr myWorld = dart::utils::SkelParser::readWorld( - "sample://data/skel/fullbody1.skel"); + "file://sample/skel/fullbody1.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); myWorld->setGravity(gravity); diff --git a/examples/osgExamples/osgAtlasPuppet/osgAtlasPuppet.cpp b/examples/osgExamples/osgAtlasPuppet/osgAtlasPuppet.cpp index 5219668e0d83..961b026b961e 100644 --- a/examples/osgExamples/osgAtlasPuppet/osgAtlasPuppet.cpp +++ b/examples/osgExamples/osgAtlasPuppet/osgAtlasPuppet.cpp @@ -511,7 +511,7 @@ SkeletonPtr createAtlas() // Parse in the atlas model DartLoader urdf; SkeletonPtr atlas = - urdf.parseSkeleton("sample://data/sdf/atlas/atlas_v3_no_head.urdf"); + urdf.parseSkeleton("file://sample/sdf/atlas/atlas_v3_no_head.urdf"); // Add a box to the root node to make it easier to click and drag double scale = 0.25; diff --git a/examples/osgExamples/osgAtlasSimbicon/main.cpp b/examples/osgExamples/osgAtlasSimbicon/main.cpp index 7521e7281ce8..f6fa5bec66f9 100644 --- a/examples/osgExamples/osgAtlasSimbicon/main.cpp +++ b/examples/osgExamples/osgAtlasSimbicon/main.cpp @@ -44,9 +44,9 @@ int main() // Load ground and Atlas robot and add them to the world dart::utils::DartLoader urdfLoader; - auto ground = urdfLoader.parseSkeleton("sample://data/sdf/atlas/ground.urdf"); + auto ground = urdfLoader.parseSkeleton("file://sample/sdf/atlas/ground.urdf"); auto atlas = dart::utils::SdfParser::readSkeleton( - "sample://data/sdf/atlas/atlas_v3_no_head.sdf"); + "file://sample/sdf/atlas/atlas_v3_no_head.sdf"); world->addSkeleton(ground); world->addSkeleton(atlas); diff --git a/examples/rigidChain/Main.cpp b/examples/rigidChain/Main.cpp index ea32fbe4a1d9..682e73950ff2 100644 --- a/examples/rigidChain/Main.cpp +++ b/examples/rigidChain/Main.cpp @@ -36,7 +36,7 @@ int main(int argc, char* argv[]) { // create and initialize the world dart::simulation::WorldPtr myWorld - = dart::utils::SkelParser::readWorld("sample://data/skel/chain.skel"); + = dart::utils::SkelParser::readWorld("file://sample/skel/chain.skel"); assert(myWorld != nullptr); // create and initialize the world diff --git a/examples/rigidCubes/Main.cpp b/examples/rigidCubes/Main.cpp index a5a796257be0..c9075071ff43 100644 --- a/examples/rigidCubes/Main.cpp +++ b/examples/rigidCubes/Main.cpp @@ -38,7 +38,7 @@ int main(int argc, char* argv[]) { // create and initialize the world dart::simulation::WorldPtr myWorld - = dart::utils::SkelParser::readWorld("sample://data/skel/cubes.skel"); + = dart::utils::SkelParser::readWorld("file://sample/skel/cubes.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); myWorld->setGravity(gravity); diff --git a/examples/rigidLoop/Main.cpp b/examples/rigidLoop/Main.cpp index 09f86916fdf1..6f9ca21bb5e3 100644 --- a/examples/rigidLoop/Main.cpp +++ b/examples/rigidLoop/Main.cpp @@ -44,7 +44,7 @@ int main(int argc, char* argv[]) // load a skeleton file // create and initialize the world dart::simulation::WorldPtr myWorld - = utils::SkelParser::readWorld("sample://data/skel/chain.skel"); + = utils::SkelParser::readWorld("file://sample/skel/chain.skel"); assert(myWorld != nullptr); // create and initialize the world diff --git a/examples/vehicle/Main.cpp b/examples/vehicle/Main.cpp index 5a36db720861..984c2293b3a1 100644 --- a/examples/vehicle/Main.cpp +++ b/examples/vehicle/Main.cpp @@ -43,7 +43,7 @@ int main(int argc, char* argv[]) using namespace utils; // create and initialize the world - WorldPtr myWorld = SkelParser::readWorld("sample://data/skel/vehicle.skel"); + WorldPtr myWorld = SkelParser::readWorld("file://sample/skel/vehicle.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); myWorld->setGravity(gravity); diff --git a/unittests/comprehensive/test_Collision.cpp b/unittests/comprehensive/test_Collision.cpp index e6e5c0ebd8d0..5dfa9d4c1fac 100644 --- a/unittests/comprehensive/test_Collision.cpp +++ b/unittests/comprehensive/test_Collision.cpp @@ -1107,7 +1107,7 @@ TEST_F(COLLISION, CollisionOfPrescribedJoints) // Load world and skeleton WorldPtr world = SkelParser::readWorld( - "sample://data/skel/test/collision_of_prescribed_joints_test.skel"); + "file://sample/skel/test/collision_of_prescribed_joints_test.skel"); world->setTimeStep(timeStep); EXPECT_TRUE(world != nullptr); EXPECT_NEAR(world->getTimeStep(), timeStep, tol); diff --git a/unittests/comprehensive/test_Dynamics.cpp b/unittests/comprehensive/test_Dynamics.cpp index bb16a047657a..cf1c1b89a70d 100644 --- a/unittests/comprehensive/test_Dynamics.cpp +++ b/unittests/comprehensive/test_Dynamics.cpp @@ -2034,7 +2034,7 @@ TEST_F(DynamicsTest, HybridDynamics) // Load world and skeleton WorldPtr world = utils::SkelParser::readWorld( - "sample://data/skel/test/hybrid_dynamics_test.skel"); + "file://sample/skel/test/hybrid_dynamics_test.skel"); world->setTimeStep(timeStep); EXPECT_TRUE(world != nullptr); EXPECT_NEAR(world->getTimeStep(), timeStep, tol); diff --git a/unittests/comprehensive/test_Joints.cpp b/unittests/comprehensive/test_Joints.cpp index 130dc6df48a5..0afb48885cd1 100644 --- a/unittests/comprehensive/test_Joints.cpp +++ b/unittests/comprehensive/test_Joints.cpp @@ -386,7 +386,7 @@ TEST_F(JOINTS, COMMAND_LIMIT) { simulation::WorldPtr myWorld = utils::SkelParser::readWorld( - "sample://data/skel/test/joint_limit_test.skel"); + "file://sample/skel/test/joint_limit_test.skel"); EXPECT_TRUE(myWorld != nullptr); dynamics::SkeletonPtr pendulum = myWorld->getSkeleton("double_pendulum"); @@ -428,7 +428,7 @@ TEST_F(JOINTS, POSITION_LIMIT) simulation::WorldPtr myWorld = utils::SkelParser::readWorld( - "sample://data/skel/test/joint_limit_test.skel"); + "file://sample/skel/test/joint_limit_test.skel"); EXPECT_TRUE(myWorld != nullptr); myWorld->setGravity(Eigen::Vector3d(0.0, 0.0, 0.0)); @@ -503,7 +503,7 @@ void testJointCoulombFrictionForce(double _timeStep) simulation::WorldPtr myWorld = utils::SkelParser::readWorld( - "sample://data/skel/test/joint_friction_test.skel"); + "file://sample/skel/test/joint_friction_test.skel"); EXPECT_TRUE(myWorld != nullptr); myWorld->setGravity(Eigen::Vector3d(0.0, 0.0, 0.0)); @@ -816,7 +816,7 @@ TEST_F(JOINTS, JOINT_COULOMB_FRICTION_AND_POSITION_LIMIT) simulation::WorldPtr myWorld = utils::SkelParser::readWorld( - "sample://data/skel/test/joint_friction_test.skel"); + "file://sample/skel/test/joint_friction_test.skel"); EXPECT_TRUE(myWorld != nullptr); myWorld->setGravity(Eigen::Vector3d(0.0, 0.0, 0.0)); diff --git a/unittests/unit/test_FileInfoWorld.cpp b/unittests/unit/test_FileInfoWorld.cpp index 501084fcefa4..013a79d29a05 100644 --- a/unittests/unit/test_FileInfoWorld.cpp +++ b/unittests/unit/test_FileInfoWorld.cpp @@ -58,7 +58,7 @@ TEST(FileInfoWorld, Basic) FileInfoWorld worldFile; WorldPtr world = SkelParser::readWorld( - "sample://data/skel/test/file_info_world_test.skel"); + "file://sample/skel/test/file_info_world_test.skel"); EXPECT_TRUE(world != nullptr); Recording* recording1 = nullptr; diff --git a/unittests/unit/test_SampleResourceRetriever.cpp b/unittests/unit/test_SampleResourceRetriever.cpp index 81d68099c178..89edb55ce848 100644 --- a/unittests/unit/test_SampleResourceRetriever.cpp +++ b/unittests/unit/test_SampleResourceRetriever.cpp @@ -38,8 +38,8 @@ using namespace dart; TEST(SampleResourceRetriever, SkelFileExists) { auto retriever = utils::SampleResourceRetriever::create(); - EXPECT_TRUE(retriever->exists("sample://data/skel/shapes.skel")); - auto sampleData = retriever->retrieve("sample://data/skel/shapes.skel"); + EXPECT_TRUE(retriever->exists("file://sample/skel/shapes.skel")); + auto sampleData = retriever->retrieve("file://sample/skel/shapes.skel"); EXPECT_TRUE(sampleData != nullptr); } diff --git a/unittests/unit/test_SdfParser.cpp b/unittests/unit/test_SdfParser.cpp index 8676e1b5b3ab..66d678fe7eac 100644 --- a/unittests/unit/test_SdfParser.cpp +++ b/unittests/unit/test_SdfParser.cpp @@ -52,7 +52,7 @@ TEST(SdfParser, SDFSingleBodyWithoutJoint) // Regression test for #444 WorldPtr world = SdfParser::readWorld( - "sample://data/sdf/test/single_bodynode_skeleton.world"); + "file://sample/sdf/test/single_bodynode_skeleton.world"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel = world->getSkeleton(0); @@ -77,12 +77,12 @@ TEST(SdfParser, ParsingSDFFiles) // Create a list of sdf files to test with where the sdf files contains World std::vector worldFiles; - worldFiles.push_back("sample://data/sdf/benchmark.world"); - worldFiles.push_back("sample://data/sdf/double_pendulum.world"); - worldFiles.push_back("sample://data/sdf/double_pendulum_with_base.world"); - worldFiles.push_back("sample://data/sdf/empty.world"); - worldFiles.push_back("sample://data/sdf/ground.world"); - worldFiles.push_back("sample://data/sdf/test/single_bodynode_skeleton.world"); + worldFiles.push_back("file://sample/sdf/benchmark.world"); + worldFiles.push_back("file://sample/sdf/double_pendulum.world"); + worldFiles.push_back("file://sample/sdf/double_pendulum_with_base.world"); + worldFiles.push_back("file://sample/sdf/empty.world"); + worldFiles.push_back("file://sample/sdf/ground.world"); + worldFiles.push_back("file://sample/sdf/test/single_bodynode_skeleton.world"); std::vector worlds; for (const auto& worldFile : worldFiles) @@ -99,8 +99,8 @@ TEST(SdfParser, ParsingSDFFiles) // Create another list of sdf files to test with where the sdf files contains // Skeleton std::vector skeletonFiles; - skeletonFiles.push_back("sample://data/sdf/atlas/atlas_v3_no_head.sdf"); - skeletonFiles.push_back("sample://data/sdf/atlas/atlas_v3_no_head_soft_feet.sdf"); + skeletonFiles.push_back("file://sample/sdf/atlas/atlas_v3_no_head.sdf"); + skeletonFiles.push_back("file://sample/sdf/atlas/atlas_v3_no_head_soft_feet.sdf"); auto world = std::make_shared(); std::vector skeletons; @@ -122,7 +122,7 @@ TEST(SdfParser, ParsingSDFFiles) //============================================================================== TEST(SdfParser, ReadMaterial) { - std::string sdf_filename = "sample://data/sdf/quad.sdf"; + std::string sdf_filename = "file://sample/sdf/quad.sdf"; SkeletonPtr skeleton = SdfParser::readSkeleton(sdf_filename); EXPECT_TRUE(nullptr != skeleton); auto bodynode = skeleton->getBodyNode(0); diff --git a/unittests/unit/test_SkelParser.cpp b/unittests/unit/test_SkelParser.cpp index 7302a65157b3..18f551caf7ff 100644 --- a/unittests/unit/test_SkelParser.cpp +++ b/unittests/unit/test_SkelParser.cpp @@ -301,7 +301,7 @@ TEST(SkelParser, PlanarJoint) TEST(SKEL_PARSER, JointActuatorType) { WorldPtr world = SkelParser::readWorld( - "sample://data/skel/test/joint_actuator_type_test.skel"); + "file://sample/skel/test/joint_actuator_type_test.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); @@ -334,7 +334,7 @@ TEST(SKEL_PARSER, JointActuatorType) TEST(SkelParser, DofAttributes) { WorldPtr world = SkelParser::readWorld( - "sample://data/skel/test/dof_attribute_test.skel"); + "file://sample/skel/test/dof_attribute_test.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); @@ -412,7 +412,7 @@ TEST(SkelParser, JointDynamicsElements) { WorldPtr world = SkelParser::readWorld( - "sample://data/skel/test/joint_dynamics_elements_test.skel"); + "file://sample/skel/test/joint_dynamics_elements_test.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); From 162b7a842ee737c03339c6d6554954748fe69e46 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Mon, 30 Jan 2017 23:48:56 -0500 Subject: [PATCH 05/14] Use URI in tests if applicable --- CMakeLists.txt | 24 +-- dart/config.hpp.in | 2 +- dart/utils/urdf/DartLoader.cpp | 2 +- dart/utils/urdf/urdf_world_parser.cpp | 33 +++-- dart/utils/urdf/urdf_world_parser.hpp | 2 +- examples/atlasSimbicon/Main.cpp | 2 +- examples/bipedStand/Main.cpp | 2 +- examples/jointConstraints/Main.cpp | 2 +- examples/mixedChain/Main.cpp | 2 +- examples/operationalSpaceControl/Main.cpp | 4 +- .../osgOperationalSpaceControl.cpp | 4 +- .../osgSoftBodies/osgSoftBodies.cpp | 2 +- examples/rigidShapes/Main.cpp | 2 +- examples/softBodies/Main.cpp | 2 +- examples/speedTest/Main.cpp | 38 ++--- .../tutorialBiped-Finished.cpp | 4 +- tutorials/tutorialBiped/tutorialBiped.cpp | 2 +- .../tutorialDominoes-Finished.cpp | 2 +- unittests/comprehensive/test_Constraint.cpp | 38 ++--- unittests/comprehensive/test_Dynamics.cpp | 139 +++++++++--------- .../comprehensive/test_ForwardKinematics.cpp | 4 +- unittests/comprehensive/test_Skeleton.cpp | 44 +++--- unittests/comprehensive/test_SoftDynamics.cpp | 2 +- unittests/comprehensive/test_World.cpp | 80 +++++----- unittests/unit/test_DartLoader.cpp | 14 +- .../unit/test_PackageResourceRetriever.cpp | 68 ++++----- .../unit/test_SampleResourceRetriever.cpp | 15 +- unittests/unit/test_SkelParser.cpp | 14 +- unittests/unit/test_VskParser.cpp | 8 +- 29 files changed, 286 insertions(+), 271 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f8152f2995ff..245f4bb18cba 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -29,12 +29,9 @@ set(INCLUDE_INSTALL_DIR "include") set(LIBRARY_INSTALL_DIR "lib") set(CONFIG_INSTALL_DIR "share/${PROJECT_NAME}/cmake") -if(WIN32) - set() -else() -endif() - -set(DART_DATA_INSTALL_REL_PATH "share/doc/${PROJECT_NAME}") +# Set relative location to install additional documentation (sample data, +# examples, and tutorials) +set(DART_ADDITIONAL_DOCUMENTATION_INSTALL_PATH "share/doc/${PROJECT_NAME}") set(CMAKE_DEBUG_POSTFIX "d") set(CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/cmake") @@ -52,8 +49,6 @@ if(WIN32) set(CMAKE_INSTALL_PREFIX "C:/Golems" CACHE PATH "Install prefix" FORCE) endif() -message(STATUS "CMAKE_INSTALL_DOCDIR: ${CMAKE_INSTALL_DOCDIR}") - #=============================================================================== # Project settings #=============================================================================== @@ -388,11 +383,20 @@ install(FILES ${PC_CONFIG_OUT} DESTINATION lib/pkgconfig) install(FILES package.xml DESTINATION share/${PROJECT_NAME}) #=============================================================================== -# Install Misc. +# Install sample data, examples, and tutorials #=============================================================================== +# Sample data install(DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/data" - DESTINATION ${DART_DATA_INSTALL_REL_PATH}) + DESTINATION ${DART_ADDITIONAL_DOCUMENTATION_INSTALL_PATH}) + +# Examples source +install(DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/examples" + DESTINATION ${DART_ADDITIONAL_DOCUMENTATION_INSTALL_PATH}) + +# Tutorials source +install(DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/tutorials" + DESTINATION ${DART_ADDITIONAL_DOCUMENTATION_INSTALL_PATH}) #=============================================================================== # Uninstall diff --git a/dart/config.hpp.in b/dart/config.hpp.in index 89adaaa3c121..65b274c35f6f 100644 --- a/dart/config.hpp.in +++ b/dart/config.hpp.in @@ -65,7 +65,7 @@ #define DART_DATA_PATH "@CMAKE_SOURCE_DIR@/data/" #define DART_DATA_LOCAL_PATH "@CMAKE_SOURCE_DIR@/data/" -#define DART_DATA_GLOBAL_PATH "@CMAKE_INSTALL_PREFIX@/@DART_DATA_INSTALL_REL_PATH@/data/" +#define DART_DATA_GLOBAL_PATH "@CMAKE_INSTALL_PREFIX@/@DART_ADDITIONAL_DOCUMENTATION_INSTALL_PATH@/data/" // See #451 #cmakedefine01 ASSIMP_AISCENE_CTOR_DTOR_DEFINED diff --git a/dart/utils/urdf/DartLoader.cpp b/dart/utils/urdf/DartLoader.cpp index b751eeed68df..0e17ec89aa69 100644 --- a/dart/utils/urdf/DartLoader.cpp +++ b/dart/utils/urdf/DartLoader.cpp @@ -151,7 +151,7 @@ simulation::WorldPtr DartLoader::parseWorldString( } std::shared_ptr worldInterface = - urdf_parsing::parseWorldURDF(_urdfString, _baseUri); + urdf_parsing::parseWorldURDF(_urdfString, _baseUri, resourceRetriever); if(!worldInterface) { diff --git a/dart/utils/urdf/urdf_world_parser.cpp b/dart/utils/urdf/urdf_world_parser.cpp index 5a156499352e..8a43ba63cd7d 100644 --- a/dart/utils/urdf/urdf_world_parser.cpp +++ b/dart/utils/urdf/urdf_world_parser.cpp @@ -69,7 +69,8 @@ Entity::Entity(const urdf::Entity& urdfEntity) */ std::shared_ptr parseWorldURDF( const std::string& _xml_string, - const dart::common::Uri& _baseUri) + const dart::common::Uri& _baseUri, + const common::ResourceRetrieverPtr& retriever) { TiXmlDocument xml_doc; xml_doc.Parse( _xml_string.c_str() ); @@ -145,32 +146,34 @@ std::shared_ptr parseWorldURDF( return nullptr; } - const std::string fileFullName = absoluteUri.getFilesystemPath(); entity.uri = absoluteUri; - // Parse model - std::string xml_model_string; - std::fstream xml_file( fileFullName.c_str(), std::fstream::in ); - if(!xml_file.is_open()) + // Parse model + const common::ResourcePtr resource = retriever->retrieve(absoluteUri); + if(!resource) { - dtwarn << "[parseWorldURDF] Could not open the file [" << fileFullName - << "]. Returning a nullptr.\n"; - return nullptr; + dtwarn << "[openXMLFile] Failed opening URI '" + << absoluteUri.toString() << "'.\n"; + throw std::runtime_error("Failed opening URI."); } - while( xml_file.good() ) + // C++11 guarantees that std::string has contiguous storage. + const std::size_t size = resource->getSize(); + std::string xml_model_string; + xml_model_string.resize(size); + if(resource->read(&xml_model_string.front(), size, 1) != 1) { - std::string line; - std::getline( xml_file, line ); - xml_model_string += (line + "\n"); + dtwarn << "[openXMLFile] Failed reading from URI '" + << absoluteUri.toString() << "'.\n"; + throw std::runtime_error("Failed reading from URI."); } - xml_file.close(); + entity.model = urdf::parseURDF( xml_model_string ); if( !entity.model ) { dtwarn << "[parseWorldURDF] Could not find a model named [" - << xml_model_string << "] in file [" << fileFullName + << xml_model_string << "] from [" << absoluteUri.toString() << "]. We will return a nullptr.\n"; return nullptr; } diff --git a/dart/utils/urdf/urdf_world_parser.hpp b/dart/utils/urdf/urdf_world_parser.hpp index 8a141ffe3b95..f78b0de594be 100644 --- a/dart/utils/urdf/urdf_world_parser.hpp +++ b/dart/utils/urdf/urdf_world_parser.hpp @@ -80,7 +80,7 @@ class World }; std::shared_ptr parseWorldURDF(const std::string &xml_string, - const dart::common::Uri& _baseUri); + const dart::common::Uri& _baseUri, const common::ResourceRetrieverPtr& retriever); } // namespace urdf_parsing } // namespace utils diff --git a/examples/atlasSimbicon/Main.cpp b/examples/atlasSimbicon/Main.cpp index dffdc840b02c..17672c5ca22e 100644 --- a/examples/atlasSimbicon/Main.cpp +++ b/examples/atlasSimbicon/Main.cpp @@ -54,7 +54,7 @@ int main(int argc, char* argv[]) SkeletonPtr ground = urdfLoader.parseSkeleton( "file://sample/sdf/atlas/ground.urdf"); SkeletonPtr atlas = SdfParser::readSkeleton( - DART_DATA_PATH"sdf/atlas/atlas_v3_no_head_soft_feet.sdf"); + "file://sample/sdf/atlas/atlas_v3_no_head_soft_feet.sdf"); myWorld->addSkeleton(atlas); myWorld->addSkeleton(ground); diff --git a/examples/bipedStand/Main.cpp b/examples/bipedStand/Main.cpp index a15b5904f1c4..86e833630d1a 100644 --- a/examples/bipedStand/Main.cpp +++ b/examples/bipedStand/Main.cpp @@ -39,7 +39,7 @@ int main(int argc, char* argv[]) { // create and initialize the world dart::simulation::WorldPtr myWorld - = dart::utils::SkelParser::readWorld(DART_DATA_PATH"skel/fullbody1.skel"); + = dart::utils::SkelParser::readWorld("file://sample/skel/fullbody1.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); diff --git a/examples/jointConstraints/Main.cpp b/examples/jointConstraints/Main.cpp index 937392388d6d..8a87fc9348cf 100644 --- a/examples/jointConstraints/Main.cpp +++ b/examples/jointConstraints/Main.cpp @@ -45,7 +45,7 @@ int main(int argc, char* argv[]) // load a skeleton file // create and initialize the world dart::simulation::WorldPtr myWorld - = utils::SkelParser::readWorld(DART_DATA_PATH"skel/fullbody1.skel"); + = utils::SkelParser::readWorld("file://sample/skel/fullbody1.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); diff --git a/examples/mixedChain/Main.cpp b/examples/mixedChain/Main.cpp index 7e43a47fa6a9..cfbeec03b228 100644 --- a/examples/mixedChain/Main.cpp +++ b/examples/mixedChain/Main.cpp @@ -47,7 +47,7 @@ int main(int argc, char* argv[]) // create and initialize the world dart::simulation::WorldPtr myWorld = dart::utils::SkelParser::readWorld( - DART_DATA_PATH"skel/test/test_articulated_bodies_10bodies.skel"); + "file://sample/skel/test/test_articulated_bodies_10bodies.skel"); assert(myWorld != nullptr); int dof = myWorld->getSkeleton(1)->getNumDofs(); diff --git a/examples/operationalSpaceControl/Main.cpp b/examples/operationalSpaceControl/Main.cpp index 595f3c972ead..48f4fd4da088 100644 --- a/examples/operationalSpaceControl/Main.cpp +++ b/examples/operationalSpaceControl/Main.cpp @@ -42,9 +42,9 @@ int main(int argc, char* argv[]) // load skeletons dart::utils::DartLoader dl; dart::dynamics::SkeletonPtr ground - = dl.parseSkeleton(DART_DATA_PATH"urdf/KR5/ground.urdf"); + = dl.parseSkeleton("file://sample/urdf/KR5/ground.urdf"); dart::dynamics::SkeletonPtr robot - = dl.parseSkeleton(DART_DATA_PATH"urdf/KR5/KR5 sixx R650.urdf"); + = dl.parseSkeleton("file://sample/urdf/KR5/KR5 sixx R650.urdf"); world->addSkeleton(ground); world->addSkeleton(robot); diff --git a/examples/osgExamples/osgOperationalSpaceControl/osgOperationalSpaceControl.cpp b/examples/osgExamples/osgOperationalSpaceControl/osgOperationalSpaceControl.cpp index c9e673ebcba1..85748e618c46 100644 --- a/examples/osgExamples/osgOperationalSpaceControl/osgOperationalSpaceControl.cpp +++ b/examples/osgExamples/osgOperationalSpaceControl/osgOperationalSpaceControl.cpp @@ -253,7 +253,7 @@ int main() // Load the robot dart::dynamics::SkeletonPtr robot = - loader.parseSkeleton(DART_DATA_PATH"urdf/KR5/KR5 sixx R650.urdf"); + loader.parseSkeleton("file://sample/urdf/KR5/KR5 sixx R650.urdf"); world->addSkeleton(robot); // Set the colors of the models to obey the shape's color specification @@ -275,7 +275,7 @@ int main() // Load the ground dart::dynamics::SkeletonPtr ground = - loader.parseSkeleton(DART_DATA_PATH"urdf/KR5/ground.urdf"); + loader.parseSkeleton("file://sample/urdf/KR5/ground.urdf"); world->addSkeleton(ground); // Rotate and move the ground so that z is upwards diff --git a/examples/osgExamples/osgSoftBodies/osgSoftBodies.cpp b/examples/osgExamples/osgSoftBodies/osgSoftBodies.cpp index 707abe1f79f1..b72538f0aab2 100644 --- a/examples/osgExamples/osgSoftBodies/osgSoftBodies.cpp +++ b/examples/osgExamples/osgSoftBodies/osgSoftBodies.cpp @@ -212,7 +212,7 @@ int main() using namespace dart::dynamics; dart::simulation::WorldPtr world = - dart::utils::SkelParser::readWorld(DART_DATA_PATH"skel/softBodies.skel"); + dart::utils::SkelParser::readWorld("file://sample/skel/softBodies.skel"); osg::ref_ptr node = new RecordingWorld(world); diff --git a/examples/rigidShapes/Main.cpp b/examples/rigidShapes/Main.cpp index 809b1a231138..8cec9f80427f 100644 --- a/examples/rigidShapes/Main.cpp +++ b/examples/rigidShapes/Main.cpp @@ -46,7 +46,7 @@ int main(int argc, char* argv[]) // load a skeleton file // create and initialize the world dart::simulation::WorldPtr myWorld - = dart::utils::SkelParser::readWorld(DART_DATA_PATH"skel/shapes.skel"); + = dart::utils::SkelParser::readWorld("file://sample/skel/shapes.skel"); assert(myWorld != NULL); // create a window and link it to the world diff --git a/examples/softBodies/Main.cpp b/examples/softBodies/Main.cpp index d2f334b9aa3b..120b6f41ef33 100644 --- a/examples/softBodies/Main.cpp +++ b/examples/softBodies/Main.cpp @@ -47,7 +47,7 @@ int main(int argc, char* argv[]) // create and initialize the world dart::simulation::WorldPtr myWorld = dart::utils::SkelParser::readWorld( - DART_DATA_PATH"skel/softBodies.skel"); + "file://sample/skel/softBodies.skel"); assert(myWorld != nullptr); for(std::size_t i=0; igetNumSkeletons(); ++i) diff --git a/examples/speedTest/Main.cpp b/examples/speedTest/Main.cpp index 7dd862703d0a..01845f4cafa9 100644 --- a/examples/speedTest/Main.cpp +++ b/examples/speedTest/Main.cpp @@ -164,25 +164,25 @@ void print_results(const std::vector& result) std::vector getSceneFiles() { std::vector scenes; - scenes.push_back(DART_DATA_PATH"skel/test/chainwhipa.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/single_pendulum.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/single_pendulum_euler_joint.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/single_pendulum_ball_joint.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/double_pendulum.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/double_pendulum_euler_joint.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/double_pendulum_ball_joint.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/serial_chain_revolute_joint.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/serial_chain_eulerxyz_joint.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint_20.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint_40.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/simple_tree_structure.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/simple_tree_structure_euler_joint.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/simple_tree_structure_ball_joint.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/tree_structure.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/tree_structure_euler_joint.skel"); - scenes.push_back(DART_DATA_PATH"skel/test/tree_structure_ball_joint.skel"); - scenes.push_back(DART_DATA_PATH"skel/fullbody1.skel"); + scenes.push_back("file://sample/skel/test/chainwhipa.skel"); + scenes.push_back("file://sample/skel/test/single_pendulum.skel"); + scenes.push_back("file://sample/skel/test/single_pendulum_euler_joint.skel"); + scenes.push_back("file://sample/skel/test/single_pendulum_ball_joint.skel"); + scenes.push_back("file://sample/skel/test/double_pendulum.skel"); + scenes.push_back("file://sample/skel/test/double_pendulum_euler_joint.skel"); + scenes.push_back("file://sample/skel/test/double_pendulum_ball_joint.skel"); + scenes.push_back("file://sample/skel/test/serial_chain_revolute_joint.skel"); + scenes.push_back("file://sample/skel/test/serial_chain_eulerxyz_joint.skel"); + scenes.push_back("file://sample/skel/test/serial_chain_ball_joint.skel"); + scenes.push_back("file://sample/skel/test/serial_chain_ball_joint_20.skel"); + scenes.push_back("file://sample/skel/test/serial_chain_ball_joint_40.skel"); + scenes.push_back("file://sample/skel/test/simple_tree_structure.skel"); + scenes.push_back("file://sample/skel/test/simple_tree_structure_euler_joint.skel"); + scenes.push_back("file://sample/skel/test/simple_tree_structure_ball_joint.skel"); + scenes.push_back("file://sample/skel/test/tree_structure.skel"); + scenes.push_back("file://sample/skel/test/tree_structure_euler_joint.skel"); + scenes.push_back("file://sample/skel/test/tree_structure_ball_joint.skel"); + scenes.push_back("file://sample/skel/fullbody1.skel"); return scenes; } diff --git a/tutorials/tutorialBiped-Finished/tutorialBiped-Finished.cpp b/tutorials/tutorialBiped-Finished/tutorialBiped-Finished.cpp index d6aea3408158..8baefbd68742 100644 --- a/tutorials/tutorialBiped-Finished/tutorialBiped-Finished.cpp +++ b/tutorials/tutorialBiped-Finished/tutorialBiped-Finished.cpp @@ -299,7 +299,7 @@ class MyWindow : public SimWindow SkeletonPtr loadBiped() { // Create the world with a skeleton - WorldPtr world = SkelParser::readWorld(DART_DATA_PATH"skel/biped.skel"); + WorldPtr world = SkelParser::readWorld("file://sample/skel/biped.skel"); assert(world != nullptr); SkeletonPtr biped = world->getSkeleton("biped"); @@ -337,7 +337,7 @@ void setInitialPose(SkeletonPtr biped) void modifyBipedWithSkateboard(SkeletonPtr biped) { // Load the Skeleton from a file - WorldPtr world = SkelParser::readWorld(DART_DATA_PATH"skel/skateboard.skel"); + WorldPtr world = SkelParser::readWorld("file://sample/skel/skateboard.skel"); SkeletonPtr skateboard = world->getSkeleton(0); diff --git a/tutorials/tutorialBiped/tutorialBiped.cpp b/tutorials/tutorialBiped/tutorialBiped.cpp index 28c362f2fe21..1432dd012c75 100644 --- a/tutorials/tutorialBiped/tutorialBiped.cpp +++ b/tutorials/tutorialBiped/tutorialBiped.cpp @@ -234,7 +234,7 @@ SkeletonPtr loadBiped() // Lesson 1 // Create the world with a skeleton - WorldPtr world = SkelParser::readWorld(DART_DATA_PATH"skel/biped.skel"); + WorldPtr world = SkelParser::readWorld("file://sample/skel/biped.skel"); assert(world != nullptr); SkeletonPtr biped = world->getSkeleton("biped"); diff --git a/tutorials/tutorialDominoes-Finished/tutorialDominoes-Finished.cpp b/tutorials/tutorialDominoes-Finished/tutorialDominoes-Finished.cpp index 59a2bf7980cd..6ffc9c8b7f73 100644 --- a/tutorials/tutorialDominoes-Finished/tutorialDominoes-Finished.cpp +++ b/tutorials/tutorialDominoes-Finished/tutorialDominoes-Finished.cpp @@ -467,7 +467,7 @@ SkeletonPtr createManipulator() // Load the Skeleton from a file dart::utils::DartLoader loader; SkeletonPtr manipulator = - loader.parseSkeleton(DART_DATA_PATH"urdf/KR5/KR5 sixx R650.urdf"); + loader.parseSkeleton("file://sample/urdf/KR5/KR5 sixx R650.urdf"); manipulator->setName("manipulator"); // Position its base in a reasonable way diff --git a/unittests/comprehensive/test_Constraint.cpp b/unittests/comprehensive/test_Constraint.cpp index c2eea40afb93..d27df2a906da 100644 --- a/unittests/comprehensive/test_Constraint.cpp +++ b/unittests/comprehensive/test_Constraint.cpp @@ -66,25 +66,25 @@ class ConstraintTest : public ::testing::Test //============================================================================== void ConstraintTest::SetUp() { - list.push_back(DART_DATA_PATH"skel/test/chainwhipa.skel"); - list.push_back(DART_DATA_PATH"skel/test/single_pendulum.skel"); - list.push_back(DART_DATA_PATH"skel/test/single_pendulum_euler_joint.skel"); - list.push_back(DART_DATA_PATH"skel/test/single_pendulum_ball_joint.skel"); - list.push_back(DART_DATA_PATH"skel/test/double_pendulum.skel"); - list.push_back(DART_DATA_PATH"skel/test/double_pendulum_euler_joint.skel"); - list.push_back(DART_DATA_PATH"skel/test/double_pendulum_ball_joint.skel"); - list.push_back(DART_DATA_PATH"skel/test/serial_chain_revolute_joint.skel"); - list.push_back(DART_DATA_PATH"skel/test/serial_chain_eulerxyz_joint.skel"); - list.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint.skel"); - list.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint_20.skel"); - list.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint_40.skel"); - list.push_back(DART_DATA_PATH"skel/test/simple_tree_structure.skel"); - list.push_back(DART_DATA_PATH"skel/test/simple_tree_structure_euler_joint.skel"); - list.push_back(DART_DATA_PATH"skel/test/simple_tree_structure_ball_joint.skel"); - list.push_back(DART_DATA_PATH"skel/test/tree_structure.skel"); - list.push_back(DART_DATA_PATH"skel/test/tree_structure_euler_joint.skel"); - list.push_back(DART_DATA_PATH"skel/test/tree_structure_ball_joint.skel"); - list.push_back(DART_DATA_PATH"skel/fullbody1.skel"); + list.push_back("file://sample/skel/test/chainwhipa.skel"); + list.push_back("file://sample/skel/test/single_pendulum.skel"); + list.push_back("file://sample/skel/test/single_pendulum_euler_joint.skel"); + list.push_back("file://sample/skel/test/single_pendulum_ball_joint.skel"); + list.push_back("file://sample/skel/test/double_pendulum.skel"); + list.push_back("file://sample/skel/test/double_pendulum_euler_joint.skel"); + list.push_back("file://sample/skel/test/double_pendulum_ball_joint.skel"); + list.push_back("file://sample/skel/test/serial_chain_revolute_joint.skel"); + list.push_back("file://sample/skel/test/serial_chain_eulerxyz_joint.skel"); + list.push_back("file://sample/skel/test/serial_chain_ball_joint.skel"); + list.push_back("file://sample/skel/test/serial_chain_ball_joint_20.skel"); + list.push_back("file://sample/skel/test/serial_chain_ball_joint_40.skel"); + list.push_back("file://sample/skel/test/simple_tree_structure.skel"); + list.push_back("file://sample/skel/test/simple_tree_structure_euler_joint.skel"); + list.push_back("file://sample/skel/test/simple_tree_structure_ball_joint.skel"); + list.push_back("file://sample/skel/test/tree_structure.skel"); + list.push_back("file://sample/skel/test/tree_structure_euler_joint.skel"); + list.push_back("file://sample/skel/test/tree_structure_ball_joint.skel"); + list.push_back("file://sample/skel/fullbody1.skel"); } //============================================================================== diff --git a/unittests/comprehensive/test_Dynamics.cpp b/unittests/comprehensive/test_Dynamics.cpp index cf1c1b89a70d..855863b8b342 100644 --- a/unittests/comprehensive/test_Dynamics.cpp +++ b/unittests/comprehensive/test_Dynamics.cpp @@ -52,8 +52,8 @@ using namespace dart; class DynamicsTest : public ::testing::Test { public: - // Get Skel file list to test. - const std::vector& getList() const; + // Get Skel file URI to test. + const std::vector& getList() const; // Get reference frames const std::vector& getRefFrames() const; @@ -71,47 +71,47 @@ class DynamicsTest : public ::testing::Test // Compare velocities computed by recursive method, Jacobian, and finite // difference. - void testJacobians(const std::string& _fileName); + void testJacobians(const common::Uri& uri); // Compare velocities and accelerations with actual vaules and approximates // using finite differece method. - void testFiniteDifferenceGeneralizedCoordinates(const std::string& _fileName); + void testFiniteDifferenceGeneralizedCoordinates(const common::Uri& uri); // Compare spatial velocities computed by forward kinematics and finite // difference. - void testFiniteDifferenceBodyNodeVelocity(const std::string& _fileName); + void testFiniteDifferenceBodyNodeVelocity(const common::Uri& uri); // Compare accelerations computed by recursive method, Jacobian, and finite // difference. - void testFiniteDifferenceBodyNodeAcceleration(const std::string& _fileName); + void testFiniteDifferenceBodyNodeAcceleration(const common::Uri& uri); // Test if the recursive forward kinematics algorithm computes // transformations, spatial velocities, and spatial accelerations correctly. - void testForwardKinematics(const std::string& _fileName); + void testForwardKinematics(const common::Uri& uri); // Compare dynamics terms in equations of motion such as mass matrix, mass // inverse matrix, Coriolis force vector, gravity force vector, and external // force vector. - void compareEquationsOfMotion(const std::string& _fileName); + void compareEquationsOfMotion(const common::Uri& uri); // Test skeleton's COM and its related quantities. - void testCenterOfMass(const std::string& _fileName); + void testCenterOfMass(const common::Uri& uri); // Test if the com acceleration is equal to the gravity - void testCenterOfMassFreeFall(const std::string& _fileName); + void testCenterOfMassFreeFall(const common::Uri& uri); // - void testConstraintImpulse(const std::string& _fileName); + void testConstraintImpulse(const common::Uri& uri); // Test impulse based dynamics - void testImpulseBasedDynamics(const std::string& _fileName); + void testImpulseBasedDynamics(const common::Uri& uri); protected: // Sets up the test fixture. void SetUp() override; // Skel file list. - std::vector fileList; + std::vector fileList; std::vector refFrames; }; @@ -120,25 +120,25 @@ class DynamicsTest : public ::testing::Test void DynamicsTest::SetUp() { // Create a list of skel files to test with - fileList.push_back(DART_DATA_PATH"skel/test/chainwhipa.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/single_pendulum.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/single_pendulum_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/single_pendulum_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/double_pendulum.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/double_pendulum_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/double_pendulum_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_revolute_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_eulerxyz_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint_20.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint_40.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/simple_tree_structure.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/simple_tree_structure_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/simple_tree_structure_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/tree_structure.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/tree_structure_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/tree_structure_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/fullbody1.skel"); + fileList.push_back("file://sample/skel/test/chainwhipa.skel"); + fileList.push_back("file://sample/skel/test/single_pendulum.skel"); + fileList.push_back("file://sample/skel/test/single_pendulum_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/single_pendulum_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/double_pendulum.skel"); + fileList.push_back("file://sample/skel/test/double_pendulum_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/double_pendulum_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_revolute_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_eulerxyz_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_20.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_40.skel"); + fileList.push_back("file://sample/skel/test/simple_tree_structure.skel"); + fileList.push_back("file://sample/skel/test/simple_tree_structure_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/simple_tree_structure_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/tree_structure.skel"); + fileList.push_back("file://sample/skel/test/tree_structure_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/tree_structure_ball_joint.skel"); + fileList.push_back("file://sample/skel/fullbody1.skel"); // Create a list of reference frames to use during tests refFrames.push_back(new SimpleFrame(Frame::World(), "refFrame1")); @@ -150,7 +150,7 @@ void DynamicsTest::SetUp() } //============================================================================== -const std::vector& DynamicsTest::getList() const +const std::vector& DynamicsTest::getList() const { return fileList; } @@ -560,7 +560,7 @@ void compareBodyNodeFkToJacobian(const BodyNode* bn, } //============================================================================== -void DynamicsTest::testJacobians(const std::string& _fileName) +void DynamicsTest::testJacobians(const common::Uri& uri) { using namespace std; using namespace Eigen; @@ -586,7 +586,7 @@ void DynamicsTest::testJacobians(const std::string& _fileName) Vector3d gravity(0.0, -9.81, 0.0); // load skeleton - WorldPtr world = SkelParser::readWorld(_fileName); + WorldPtr world = SkelParser::readWorld(uri); assert(world != nullptr); world->setGravity(gravity); @@ -677,7 +677,7 @@ void DynamicsTest::testJacobians(const std::string& _fileName) //============================================================================== void DynamicsTest::testFiniteDifferenceGeneralizedCoordinates( - const std::string& _fileName) + const common::Uri& uri) { using namespace std; using namespace Eigen; @@ -704,7 +704,7 @@ void DynamicsTest::testFiniteDifferenceGeneralizedCoordinates( double TOLERANCE = 5e-4; // load skeleton - WorldPtr world = SkelParser::readWorld(_fileName); + WorldPtr world = SkelParser::readWorld(uri); assert(world != nullptr); world->setGravity(gravity); world->setTimeStep(timeStep); @@ -778,8 +778,7 @@ void DynamicsTest::testFiniteDifferenceGeneralizedCoordinates( } //============================================================================== -void DynamicsTest::testFiniteDifferenceBodyNodeVelocity( - const std::string& _fileName) +void DynamicsTest::testFiniteDifferenceBodyNodeVelocity(const common::Uri& uri) { using namespace std; using namespace Eigen; @@ -808,7 +807,7 @@ void DynamicsTest::testFiniteDifferenceBodyNodeVelocity( const double tol = timeStep * 1e+2; // load skeleton - WorldPtr world = SkelParser::readWorld(_fileName); + WorldPtr world = SkelParser::readWorld(uri); assert(world != nullptr); world->setGravity(gravity); world->setTimeStep(timeStep); @@ -876,7 +875,7 @@ void DynamicsTest::testFiniteDifferenceBodyNodeVelocity( //============================================================================== void DynamicsTest::testFiniteDifferenceBodyNodeAcceleration( - const std::string& _fileName) + const common::Uri& uri) { using namespace std; using namespace Eigen; @@ -903,7 +902,7 @@ void DynamicsTest::testFiniteDifferenceBodyNodeAcceleration( double timeStep = 1.0e-6; // load skeleton - WorldPtr world = SkelParser::readWorld(_fileName); + WorldPtr world = SkelParser::readWorld(uri); assert(world != nullptr); world->setGravity(gravity); world->setTimeStep(timeStep); @@ -1155,9 +1154,9 @@ void testForwardKinematicsSkeleton(const dynamics::SkeletonPtr& skel) } //============================================================================== -void DynamicsTest::testForwardKinematics(const std::string& fileName) +void DynamicsTest::testForwardKinematics(const common::Uri& uri) { - auto world = utils::SkelParser::readWorld(fileName); + auto world = utils::SkelParser::readWorld(uri); EXPECT_TRUE(world != nullptr); auto numSkeletons = world->getNumSkeletons(); @@ -1169,7 +1168,7 @@ void DynamicsTest::testForwardKinematics(const std::string& fileName) } //============================================================================== -void DynamicsTest::compareEquationsOfMotion(const std::string& _fileName) +void DynamicsTest::compareEquationsOfMotion(const common::Uri& uri) { using namespace std; using namespace Eigen; @@ -1202,7 +1201,7 @@ void DynamicsTest::compareEquationsOfMotion(const std::string& _fileName) //----------------------------- Tests ---------------------------------------- // Check whether multiplication of mass matrix and its inverse is identity // matrix. - myWorld = utils::SkelParser::readWorld(_fileName); + myWorld = utils::SkelParser::readWorld(uri); EXPECT_TRUE(myWorld != nullptr); for (std::size_t i = 0; i < myWorld->getNumSkeletons(); ++i) @@ -1381,7 +1380,7 @@ void DynamicsTest::compareEquationsOfMotion(const std::string& _fileName) if(failure) { - std::cout << "Failure occurred in the World of file: " << _fileName + std::cout << "Failure occurred in the World of file: " << uri.toString() << "\nWith Skeleton named: " << skel->getName() << "\n\n"; } } @@ -1446,7 +1445,7 @@ void compareCOMJacobianToFk(const SkeletonPtr& skel, } //============================================================================== -void DynamicsTest::testCenterOfMass(const std::string& _fileName) +void DynamicsTest::testCenterOfMass(const common::Uri& uri) { using namespace std; using namespace Eigen; @@ -1479,7 +1478,7 @@ void DynamicsTest::testCenterOfMass(const std::string& _fileName) //----------------------------- Tests ---------------------------------------- // Check whether multiplication of mass matrix and its inverse is identity // matrix. - myWorld = utils::SkelParser::readWorld(_fileName); + myWorld = utils::SkelParser::readWorld(uri); EXPECT_TRUE(myWorld != nullptr); for (std::size_t i = 0; i < myWorld->getNumSkeletons(); ++i) @@ -1602,7 +1601,7 @@ void compareCOMAccelerationToGravity(SkeletonPtr skel, } //============================================================================== -void DynamicsTest::testCenterOfMassFreeFall(const std::string& _fileName) +void DynamicsTest::testCenterOfMassFreeFall(const common::Uri& uri) { using namespace std; using namespace Eigen; @@ -1640,7 +1639,7 @@ void DynamicsTest::testCenterOfMassFreeFall(const std::string& _fileName) //----------------------------- Tests ---------------------------------------- // Check whether multiplication of mass matrix and its inverse is identity // matrix. - myWorld = utils::SkelParser::readWorld(_fileName); + myWorld = utils::SkelParser::readWorld(uri); EXPECT_TRUE(myWorld != nullptr); for (std::size_t i = 0; i < myWorld->getNumSkeletons(); ++i) @@ -1717,7 +1716,7 @@ void DynamicsTest::testCenterOfMassFreeFall(const std::string& _fileName) } //============================================================================== -void DynamicsTest::testConstraintImpulse(const std::string& _fileName) +void DynamicsTest::testConstraintImpulse(const common::Uri& uri) { using namespace std; using namespace Eigen; @@ -1744,7 +1743,7 @@ void DynamicsTest::testConstraintImpulse(const std::string& _fileName) //----------------------------- Tests ---------------------------------------- // Check whether multiplication of mass matrix and its inverse is identity // matrix. - myWorld = utils::SkelParser::readWorld(_fileName); + myWorld = utils::SkelParser::readWorld(uri); EXPECT_TRUE(myWorld != nullptr); for (std::size_t i = 0; i < myWorld->getNumSkeletons(); ++i) @@ -1811,7 +1810,7 @@ void DynamicsTest::testConstraintImpulse(const std::string& _fileName) } //============================================================================== -void DynamicsTest::testImpulseBasedDynamics(const std::string& _fileName) +void DynamicsTest::testImpulseBasedDynamics(const common::Uri& uri) { using namespace std; using namespace Eigen; @@ -1840,7 +1839,7 @@ void DynamicsTest::testImpulseBasedDynamics(const std::string& _fileName) //----------------------------- Tests ---------------------------------------- // Check whether multiplication of mass matrix and its inverse is identity // matrix. - myWorld = utils::SkelParser::readWorld(_fileName); + myWorld = utils::SkelParser::readWorld(uri); EXPECT_TRUE(myWorld != nullptr); for (std::size_t i = 0; i < myWorld->getNumSkeletons(); ++i) @@ -1914,7 +1913,7 @@ TEST_F(DynamicsTest, testJacobians) for (std::size_t i = 0; i < getList().size(); ++i) { #ifndef NDEBUG - dtdbg << getList()[i] << std::endl; + dtdbg << getList()[i].toString() << std::endl; #endif testJacobians(getList()[i]); } @@ -1926,7 +1925,7 @@ TEST_F(DynamicsTest, testFiniteDifference) for (std::size_t i = 0; i < getList().size(); ++i) { #if BUILD_TYPE_DEBUG - dtdbg << getList()[i] << std::endl; + dtdbg << getList()[i].toString() << std::endl; #endif testFiniteDifferenceGeneralizedCoordinates(getList()[i]); testFiniteDifferenceBodyNodeVelocity(getList()[i]); @@ -1940,7 +1939,7 @@ TEST_F(DynamicsTest, testForwardKinematics) for (std::size_t i = 0; i < getList().size(); ++i) { #ifndef NDEBUG - dtdbg << getList()[i] << std::endl; + dtdbg << getList()[i].toString() << std::endl; #endif testForwardKinematics(getList()[i]); } @@ -1954,20 +1953,20 @@ TEST_F(DynamicsTest, compareEquationsOfMotion) //////////////////////////////////////////////////////////////////////////// // TODO(JS): Following skel files, which contain euler joints couldn't // pass EQUATIONS_OF_MOTION, are disabled. - std::string skelFileName = getList()[i]; - if (skelFileName == DART_DATA_PATH"skel/test/double_pendulum_euler_joint.skel" - || skelFileName == DART_DATA_PATH"skel/test/chainwhipa.skel" - || skelFileName == DART_DATA_PATH"skel/test/serial_chain_eulerxyz_joint.skel" - || skelFileName == DART_DATA_PATH"skel/test/simple_tree_structure_euler_joint.skel" - || skelFileName == DART_DATA_PATH"skel/test/tree_structure_euler_joint.skel" - || skelFileName == DART_DATA_PATH"skel/fullbody1.skel") + const auto uri = getList()[i]; + if (uri.toString() == "file://sample/skel/test/double_pendulum_euler_joint.skel" + || uri.toString() == "file://sample/skel/test/chainwhipa.skel" + || uri.toString() == "file://sample/skel/test/serial_chain_eulerxyz_joint.skel" + || uri.toString() == "file://sample/skel/test/simple_tree_structure_euler_joint.skel" + || uri.toString() == "file://sample/skel/test/tree_structure_euler_joint.skel" + || uri.toString() == "file://sample/skel/fullbody1.skel") { continue; } //////////////////////////////////////////////////////////////////////////// #ifndef NDEBUG - dtdbg << getList()[i] << std::endl; + dtdbg << getList()[i].toString() << std::endl; #endif compareEquationsOfMotion(getList()[i]); } @@ -1979,7 +1978,7 @@ TEST_F(DynamicsTest, testCenterOfMass) for (std::size_t i = 0; i < getList().size(); ++i) { #ifndef NDEBUG - dtdbg << getList()[i] << std::endl; + dtdbg << getList()[i].toString() << std::endl; #endif testCenterOfMass(getList()[i]); } @@ -1991,7 +1990,7 @@ TEST_F(DynamicsTest, testCenterOfMassFreeFall) for (std::size_t i = 0; i < getList().size(); ++i) { #ifndef NDEBUG - dtdbg << getList()[i] << std::endl; + dtdbg << getList()[i].toString() << std::endl; #endif testCenterOfMassFreeFall(getList()[i]); } @@ -2003,7 +2002,7 @@ TEST_F(DynamicsTest, testConstraintImpulse) for (std::size_t i = 0; i < getList().size(); ++i) { #ifndef NDEBUG - dtdbg << getList()[i] << std::endl; + dtdbg << getList()[i].toString() << std::endl; #endif testConstraintImpulse(getList()[i]); } @@ -2015,7 +2014,7 @@ TEST_F(DynamicsTest, testImpulseBasedDynamics) for (std::size_t i = 0; i < getList().size(); ++i) { #ifndef NDEBUG - dtdbg << getList()[i] << std::endl; + dtdbg << getList()[i].toString() << std::endl; #endif testImpulseBasedDynamics(getList()[i]); } diff --git a/unittests/comprehensive/test_ForwardKinematics.cpp b/unittests/comprehensive/test_ForwardKinematics.cpp index 2ee818d085df..5294f3947121 100644 --- a/unittests/comprehensive/test_ForwardKinematics.cpp +++ b/unittests/comprehensive/test_ForwardKinematics.cpp @@ -178,7 +178,7 @@ TEST(FORWARD_KINEMATICS, JACOBIAN_PARTIAL_CHANGE) dart::utils::DartLoader loader; SkeletonPtr skeleton1 = - loader.parseSkeleton(DART_DATA_PATH"urdf/KR5/KR5 sixx R650.urdf"); + loader.parseSkeleton("file://sample/urdf/KR5/KR5 sixx R650.urdf"); SkeletonPtr skeleton2 = skeleton1->clone(); @@ -219,7 +219,7 @@ TEST(FORWARD_KINEMATICS, JACOBIAN_END_EFFECTOR_CHANGE) dart::utils::DartLoader loader; SkeletonPtr skeleton1 = - loader.parseSkeleton(DART_DATA_PATH"urdf/KR5/KR5 sixx R650.urdf"); + loader.parseSkeleton("file://sample/urdf/KR5/KR5 sixx R650.urdf"); BodyNode* last_bn1 = skeleton1->getBodyNode(skeleton1->getNumBodyNodes()-1); EndEffector* ee1 = last_bn1->createEndEffector(); diff --git a/unittests/comprehensive/test_Skeleton.cpp b/unittests/comprehensive/test_Skeleton.cpp index a488b4c09bf3..bd62004b5e19 100644 --- a/unittests/comprehensive/test_Skeleton.cpp +++ b/unittests/comprehensive/test_Skeleton.cpp @@ -46,35 +46,35 @@ using namespace math; using namespace dynamics; using namespace simulation; -std::vector getFileList() +std::vector getFileList() { - std::vector fileList; - fileList.push_back(DART_DATA_PATH"skel/test/chainwhipa.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/single_pendulum.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/single_pendulum_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/single_pendulum_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/double_pendulum.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/double_pendulum_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/double_pendulum_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_revolute_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_eulerxyz_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint_20.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint_40.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/simple_tree_structure.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/simple_tree_structure_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/simple_tree_structure_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/tree_structure.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/tree_structure_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/tree_structure_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/fullbody1.skel"); + std::vector fileList; + fileList.push_back("file://sample/skel/test/chainwhipa.skel"); + fileList.push_back("file://sample/skel/test/single_pendulum.skel"); + fileList.push_back("file://sample/skel/test/single_pendulum_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/single_pendulum_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/double_pendulum.skel"); + fileList.push_back("file://sample/skel/test/double_pendulum_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/double_pendulum_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_revolute_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_eulerxyz_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_20.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_40.skel"); + fileList.push_back("file://sample/skel/test/simple_tree_structure.skel"); + fileList.push_back("file://sample/skel/test/simple_tree_structure_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/simple_tree_structure_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/tree_structure.skel"); + fileList.push_back("file://sample/skel/test/tree_structure_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/tree_structure_ball_joint.skel"); + fileList.push_back("file://sample/skel/fullbody1.skel"); return fileList; } std::vector getSkeletons() { - std::vector fileList = getFileList(); + const auto fileList = getFileList(); std::vector worlds; for(std::size_t i=0; i fileList; - fileList.push_back(DART_DATA_PATH"skel/test/chainwhipa.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/single_pendulum.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/single_pendulum_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/single_pendulum_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/double_pendulum.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/double_pendulum_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/double_pendulum_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_revolute_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_eulerxyz_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint_20.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint_40.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/simple_tree_structure.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/simple_tree_structure_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/simple_tree_structure_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/tree_structure.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/tree_structure_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/tree_structure_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/fullbody1.skel"); + std::vector fileList; + fileList.push_back("file://sample/skel/test/chainwhipa.skel"); + fileList.push_back("file://sample/skel/test/single_pendulum.skel"); + fileList.push_back("file://sample/skel/test/single_pendulum_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/single_pendulum_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/double_pendulum.skel"); + fileList.push_back("file://sample/skel/test/double_pendulum_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/double_pendulum_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_revolute_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_eulerxyz_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_20.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_40.skel"); + fileList.push_back("file://sample/skel/test/simple_tree_structure.skel"); + fileList.push_back("file://sample/skel/test/simple_tree_structure_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/simple_tree_structure_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/tree_structure.skel"); + fileList.push_back("file://sample/skel/test/tree_structure_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/tree_structure_ball_joint.skel"); + fileList.push_back("file://sample/skel/fullbody1.skel"); std::vector worlds; for(std::size_t i=0; i fileList; - fileList.push_back(DART_DATA_PATH"skel/test/chainwhipa.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/single_pendulum.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/single_pendulum_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/single_pendulum_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/double_pendulum.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/double_pendulum_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/double_pendulum_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_revolute_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_eulerxyz_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint_20.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/serial_chain_ball_joint_40.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/simple_tree_structure.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/simple_tree_structure_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/simple_tree_structure_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/tree_structure.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/tree_structure_euler_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/test/tree_structure_ball_joint.skel"); - fileList.push_back(DART_DATA_PATH"skel/fullbody1.skel"); + std::vector fileList; + fileList.push_back("file://sample/skel/test/chainwhipa.skel"); + fileList.push_back("file://sample/skel/test/single_pendulum.skel"); + fileList.push_back("file://sample/skel/test/single_pendulum_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/single_pendulum_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/double_pendulum.skel"); + fileList.push_back("file://sample/skel/test/double_pendulum_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/double_pendulum_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_revolute_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_eulerxyz_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_20.skel"); + fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_40.skel"); + fileList.push_back("file://sample/skel/test/simple_tree_structure.skel"); + fileList.push_back("file://sample/skel/test/simple_tree_structure_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/simple_tree_structure_ball_joint.skel"); + fileList.push_back("file://sample/skel/test/tree_structure.skel"); + fileList.push_back("file://sample/skel/test/tree_structure_euler_joint.skel"); + fileList.push_back("file://sample/skel/test/tree_structure_ball_joint.skel"); + fileList.push_back("file://sample/skel/fullbody1.skel"); std::vector worlds; for(std::size_t i=0; i(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", DART_DATA_PATH"test"); + retriever.addPackageDirectory("test", "file://sample/test"); EXPECT_FALSE(retriever.exists(Uri::createFromString("package://test/foo"))); ASSERT_EQ(1u, mockRetriever->mExists.size()); @@ -72,7 +72,7 @@ TEST(PackageResourceRetriever, exists_UnsupportedUri_ReturnsFalse) { auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", DART_DATA_PATH"test"); + retriever.addPackageDirectory("test", "file://sample/test"); EXPECT_FALSE(retriever.exists(Uri::createFromString("foo://test/foo"))); EXPECT_TRUE(mockRetriever->mExists.empty()); @@ -82,14 +82,14 @@ TEST(PackageResourceRetriever, exists_UnsupportedUri_ReturnsFalse) TEST(PackageResourceRetriever, exists_StripsTrailingSlash) { #ifdef _WIN32 - const char* expected = "file:///" DART_DATA_PATH"test/foo"; + const char* expected = "file:///" "file://sample/test/foo"; #else - const char* expected = "file://" DART_DATA_PATH"test/foo"; + const char* expected = "file://" "file://sample/test/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", DART_DATA_PATH"test/"); + retriever.addPackageDirectory("test", "file://sample/test/"); EXPECT_TRUE(retriever.exists(Uri::createFromString("package://test/foo"))); ASSERT_EQ(1u, mockRetriever->mExists.size()); @@ -100,15 +100,15 @@ TEST(PackageResourceRetriever, exists_StripsTrailingSlash) TEST(PackageResourceRetriever, exists_FirstUriSucceeds) { #ifdef _WIN32 - const char* expected = "file:///" DART_DATA_PATH"test1/foo"; + const char* expected = "file:///" "file://sample/test1/foo"; #else - const char* expected = "file://" DART_DATA_PATH"test1/foo"; + const char* expected = "file://" "file://sample/test1/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", DART_DATA_PATH"test1"); - retriever.addPackageDirectory("test", DART_DATA_PATH"test2"); + retriever.addPackageDirectory("test", "file://sample/test1"); + retriever.addPackageDirectory("test", "file://sample/test2"); EXPECT_TRUE(retriever.exists(Uri::createFromString("package://test/foo"))); ASSERT_EQ(1u, mockRetriever->mExists.size()); @@ -119,17 +119,17 @@ TEST(PackageResourceRetriever, exists_FirstUriSucceeds) TEST(PackageResourceRetriever, exists_FallsBackOnSecondUri) { #ifdef _WIN32 - const char* expected1 = "file:///" DART_DATA_PATH"test1/foo"; - const char* expected2 = "file:///" DART_DATA_PATH"test2/foo"; + const char* expected1 = "file:///" "file://sample/test1/foo"; + const char* expected2 = "file:///" "file://sample/test2/foo"; #else - const char* expected1 = "file://" DART_DATA_PATH"test1/foo"; - const char* expected2 = "file://" DART_DATA_PATH"test2/foo"; + const char* expected1 = "file://" "file://sample/test1/foo"; + const char* expected2 = "file://" "file://sample/test2/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", DART_DATA_PATH"test1"); - retriever.addPackageDirectory("test", DART_DATA_PATH"test2"); + retriever.addPackageDirectory("test", "file://sample/test1"); + retriever.addPackageDirectory("test", "file://sample/test2"); EXPECT_FALSE(retriever.exists(Uri::createFromString("package://test/foo"))); ASSERT_EQ(2u, mockRetriever->mExists.size()); @@ -152,14 +152,14 @@ TEST(PackageResourceRetriever, retrieve_DelegateFails_ReturnsNull) { // GTest breaks the string concatenation. #ifdef _WIN32 - const char* expected = "file:///" DART_DATA_PATH"test/foo"; + const char* expected = "file:///" "file://sample/test/foo"; #else - const char* expected = "file://" DART_DATA_PATH"test/foo"; + const char* expected = "file://" "file://sample/test/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", DART_DATA_PATH"test"); + retriever.addPackageDirectory("test", "file://sample/test"); EXPECT_EQ(nullptr, retriever.retrieve(Uri::createFromString("package://test/foo"))); EXPECT_TRUE(mockRetriever->mExists.empty()); @@ -171,7 +171,7 @@ TEST(PackageResourceRetriever, retrieve_UnsupportedUri_ReturnsNull) { auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", DART_DATA_PATH"test"); + retriever.addPackageDirectory("test", "file://sample/test"); EXPECT_EQ(nullptr, retriever.retrieve(Uri::createFromString("foo://test/foo"))); EXPECT_TRUE(mockRetriever->mExists.empty()); @@ -181,14 +181,14 @@ TEST(PackageResourceRetriever, retrieve_UnsupportedUri_ReturnsNull) TEST(PackageResourceRetriever, retrieve_StripsTrailingSlash) { #ifdef _WIN32 - const char* expected = "file:///" DART_DATA_PATH"test/foo"; + const char* expected = "file:///" "file://sample/test/foo"; #else - const char* expected = "file://" DART_DATA_PATH"test/foo"; + const char* expected = "file://" "file://sample/test/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", DART_DATA_PATH"test/"); + retriever.addPackageDirectory("test", "file://sample/test/"); EXPECT_TRUE(retriever.retrieve(Uri::createFromString("package://test/foo")) != nullptr); EXPECT_TRUE(mockRetriever->mExists.empty()); @@ -199,15 +199,15 @@ TEST(PackageResourceRetriever, retrieve_StripsTrailingSlash) TEST(PackageResourceRetriever, retrieve_FirstUriSucceeds) { #ifdef _WIN32 - const char* expected = "file:///" DART_DATA_PATH"test1/foo"; + const char* expected = "file:///" "file://sample/test1/foo"; #else - const char* expected = "file://" DART_DATA_PATH"test1/foo"; + const char* expected = "file://" "file://sample/test1/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", DART_DATA_PATH"test1"); - retriever.addPackageDirectory("test", DART_DATA_PATH"test2"); + retriever.addPackageDirectory("test", "file://sample/test1"); + retriever.addPackageDirectory("test", "file://sample/test2"); EXPECT_TRUE(retriever.retrieve(Uri::createFromString("package://test/foo")) != nullptr); EXPECT_TRUE(mockRetriever->mExists.empty()); @@ -218,17 +218,17 @@ TEST(PackageResourceRetriever, retrieve_FirstUriSucceeds) TEST(PackageResourceRetriever, retrieve_FallsBackOnSecondUri) { #ifdef _WIN32 - const char* expected1 = "file:///" DART_DATA_PATH"test1/foo"; - const char* expected2 = "file:///" DART_DATA_PATH"test2/foo"; + const char* expected1 = "file:///" "file://sample/test1/foo"; + const char* expected2 = "file:///" "file://sample/test2/foo"; #else - const char* expected1 = "file://" DART_DATA_PATH"test1/foo"; - const char* expected2 = "file://" DART_DATA_PATH"test2/foo"; + const char* expected1 = "file://" "file://sample/test1/foo"; + const char* expected2 = "file://" "file://sample/test2/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", DART_DATA_PATH"test1"); - retriever.addPackageDirectory("test", DART_DATA_PATH"test2"); + retriever.addPackageDirectory("test", "file://sample/test1"); + retriever.addPackageDirectory("test", "file://sample/test2"); EXPECT_EQ(nullptr, retriever.retrieve(Uri::createFromString("package://test/foo"))); EXPECT_TRUE(mockRetriever->mExists.empty()); diff --git a/unittests/unit/test_SampleResourceRetriever.cpp b/unittests/unit/test_SampleResourceRetriever.cpp index 89edb55ce848..d12f4a2cbaa6 100644 --- a/unittests/unit/test_SampleResourceRetriever.cpp +++ b/unittests/unit/test_SampleResourceRetriever.cpp @@ -35,12 +35,21 @@ using namespace dart; //============================================================================== -TEST(SampleResourceRetriever, SkelFileExists) +TEST(SampleResourceRetriever, ExistsAndRetrieve) { auto retriever = utils::SampleResourceRetriever::create(); + + EXPECT_FALSE(retriever->exists("unknown://test")); + EXPECT_FALSE(retriever->exists("unknown://sample/test")); + EXPECT_FALSE(retriever->exists("file://unknown/test")); + EXPECT_FALSE(retriever->exists("file://sample/does/not/exist")); EXPECT_TRUE(retriever->exists("file://sample/skel/shapes.skel")); - auto sampleData = retriever->retrieve("file://sample/skel/shapes.skel"); - EXPECT_TRUE(sampleData != nullptr); + + EXPECT_EQ(nullptr, retriever->retrieve("unknown://test")); + EXPECT_EQ(nullptr, retriever->retrieve("unknown://sample/test")); + EXPECT_EQ(nullptr, retriever->retrieve("file://unknown/test")); + EXPECT_EQ(nullptr, retriever->retrieve("file://sample/does/not/exist")); + EXPECT_NE(nullptr, retriever->retrieve("file://sample/skel/shapes.skel")); } //============================================================================== diff --git a/unittests/unit/test_SkelParser.cpp b/unittests/unit/test_SkelParser.cpp index 18f551caf7ff..15625aaf9727 100644 --- a/unittests/unit/test_SkelParser.cpp +++ b/unittests/unit/test_SkelParser.cpp @@ -89,7 +89,7 @@ TEST(SkelParser, DataStructure) //============================================================================== TEST(SkelParser, EmptyWorld) { - WorldPtr world = SkelParser::readWorld(DART_DATA_PATH"skel/test/empty.skel"); + WorldPtr world = SkelParser::readWorld("file://sample/skel/test/empty.skel"); EXPECT_TRUE(world != nullptr); EXPECT_EQ(world->getTimeStep(), 0.001); @@ -107,7 +107,7 @@ TEST(SkelParser, EmptyWorld) TEST(SkelParser, SinglePendulum) { WorldPtr world = SkelParser::readWorld( - DART_DATA_PATH"skel/test/single_pendulum.skel"); + "file://sample/skel/test/single_pendulum.skel"); EXPECT_TRUE(world != nullptr); EXPECT_EQ(world->getTimeStep(), 0.001); @@ -127,7 +127,7 @@ TEST(SkelParser, SinglePendulum) TEST(SkelParser, SerialChain) { WorldPtr world = SkelParser::readWorld( - DART_DATA_PATH"skel/test/serial_chain_ball_joint.skel"); + "file://sample/skel/test/serial_chain_ball_joint.skel"); EXPECT_TRUE(world != nullptr); EXPECT_EQ(world->getTimeStep(), 0.001); @@ -150,7 +150,7 @@ TEST(SkelParser, VariousShapes) // world can simulate it successfully. WorldPtr world = SkelParser::readWorld( - DART_DATA_PATH"skel/test/test_shapes.skel"); + "file://sample/skel/test/test_shapes.skel"); for (auto i = 0u; i < 100; ++i) world->step(); @@ -166,7 +166,7 @@ TEST(SkelParser, RigidAndSoftBodies) using namespace utils; WorldPtr world = SkelParser::readWorld( - DART_DATA_PATH"skel/test/test_articulated_bodies.skel"); + "file://sample/skel/test/test_articulated_bodies.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); @@ -191,7 +191,7 @@ TEST(SkelParser, PlanarJoint) using namespace utils; WorldPtr world = SkelParser::readWorld( - DART_DATA_PATH"skel/test/planar_joint.skel"); + "file://sample/skel/test/planar_joint.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton1"); @@ -444,7 +444,7 @@ TEST(SkelParser, JointDynamicsElements) TEST(SkelParser, Shapes) { WorldPtr world - = SkelParser::readWorld(DART_DATA_PATH"/skel/test/test_shapes.skel"); + = SkelParser::readWorld("file://sample//skel/test/test_shapes.skel"); EXPECT_NE(world, nullptr); const auto numSkels = world->getNumSkeletons(); diff --git a/unittests/unit/test_VskParser.cpp b/unittests/unit/test_VskParser.cpp index 635d3f86b55b..0b12d06218bd 100644 --- a/unittests/unit/test_VskParser.cpp +++ b/unittests/unit/test_VskParser.cpp @@ -54,7 +54,7 @@ TEST(VskParser, EmptySkeleton) EXPECT_TRUE(world != nullptr); SkeletonPtr skeleton - = VskParser::readSkeleton(DART_DATA_PATH"vsk/test/empty.vsk"); + = VskParser::readSkeleton("file://sample/vsk/test/empty.vsk"); EXPECT_TRUE(skeleton == nullptr); world->addSkeleton(skeleton); @@ -70,17 +70,17 @@ TEST(VskParser, SingleStepSimulations) EXPECT_NE(world , nullptr); SkeletonPtr nick - = VskParser::readSkeleton(DART_DATA_PATH"vsk/Nick01.vsk"); + = VskParser::readSkeleton("file://sample/vsk/Nick01.vsk"); EXPECT_NE(nick , nullptr); EXPECT_EQ(nick->getNumMarkers(), 53u); SkeletonPtr sehoon - = VskParser::readSkeleton(DART_DATA_PATH"vsk/SehoonVSK3.vsk"); + = VskParser::readSkeleton("file://sample/vsk/SehoonVSK3.vsk"); EXPECT_NE(sehoon, nullptr); EXPECT_EQ(nick->getNumMarkers(), 53u); SkeletonPtr yuting - = VskParser::readSkeleton(DART_DATA_PATH"vsk/Yuting.vsk"); + = VskParser::readSkeleton("file://sample/vsk/Yuting.vsk"); EXPECT_NE(yuting, nullptr); EXPECT_EQ(nick->getNumMarkers(), 53u); From 764900674f0f8d924ac3ffa2c66622644513dc5c Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Tue, 31 Jan 2017 00:02:41 -0500 Subject: [PATCH 06/14] Exclude unnecessary files from installation --- CMakeLists.txt | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 245f4bb18cba..f7efe970ac58 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -392,11 +392,14 @@ install(DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/data" # Examples source install(DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/examples" - DESTINATION ${DART_ADDITIONAL_DOCUMENTATION_INSTALL_PATH}) + DESTINATION ${DART_ADDITIONAL_DOCUMENTATION_INSTALL_PATH} + PATTERN "examples/CMakeLists.txt" EXCLUDE + PATTERN "examples/osgExamples/CMakeLists.txt" EXCLUDE) # Tutorials source install(DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/tutorials" - DESTINATION ${DART_ADDITIONAL_DOCUMENTATION_INSTALL_PATH}) + DESTINATION ${DART_ADDITIONAL_DOCUMENTATION_INSTALL_PATH} + PATTERN "tutorials/CMakeLists.txt" EXCLUDE) #=============================================================================== # Uninstall From 260ce8d94b942c56368f9abb9e99e3bbf8b7c9e7 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Tue, 31 Jan 2017 00:30:18 -0500 Subject: [PATCH 07/14] Suppress verbose warnings --- dart/gui/SimWindow.cpp | 2 + dart/utils/CompositeResourceRetriever.cpp | 3 ++ dart/utils/SampleResourceRetriever.cpp | 49 +++++++++++++++-------- dart/utils/SampleResourceRetriever.hpp | 3 +- dart/utils/SkelParser.cpp | 13 +----- dart/utils/VskParser.cpp | 13 +----- dart/utils/sdf/SdfParser.cpp | 13 +----- 7 files changed, 42 insertions(+), 54 deletions(-) diff --git a/dart/gui/SimWindow.cpp b/dart/gui/SimWindow.cpp index 6d0d09df0f5d..64d61d1d2740 100644 --- a/dart/gui/SimWindow.cpp +++ b/dart/gui/SimWindow.cpp @@ -68,6 +68,8 @@ namespace gui { SimWindow::SimWindow() : Win3D() { + mWorld = std::make_shared(); + mBackground[0] = 1.0; mBackground[1] = 1.0; mBackground[2] = 1.0; diff --git a/dart/utils/CompositeResourceRetriever.cpp b/dart/utils/CompositeResourceRetriever.cpp index a83803fb7436..4d92e1c19870 100644 --- a/dart/utils/CompositeResourceRetriever.cpp +++ b/dart/utils/CompositeResourceRetriever.cpp @@ -88,6 +88,9 @@ common::ResourcePtr CompositeResourceRetriever::retrieve( = getRetrievers(_uri); for(const common::ResourceRetrieverPtr& resourceRetriever : retrievers) { + if(!resourceRetriever->exists(_uri)) + continue; + if(common::ResourcePtr resource = resourceRetriever->retrieve(_uri)) return resource; } diff --git a/dart/utils/SampleResourceRetriever.cpp b/dart/utils/SampleResourceRetriever.cpp index 65440c4c267b..6dcb396fb22f 100644 --- a/dart/utils/SampleResourceRetriever.cpp +++ b/dart/utils/SampleResourceRetriever.cpp @@ -54,14 +54,23 @@ bool SampleResourceRetriever::exists(const common::Uri& uri) if (!resolveDataUri(uri, relativePath)) return false; - for (const auto& dataPath : mDataDirectories) + if (uri.mAuthority.get() == "sample") { - common::Uri fileUri; - fileUri.fromPath(dataPath + relativePath); - - if (mLocalRetriever->exists(fileUri)) + for (const auto& dataPath : mDataDirectories) + { + common::Uri fileUri; + fileUri.fromPath(dataPath + relativePath); + + if (mLocalRetriever->exists(fileUri)) + return true; + } + } + else + { + if (mLocalRetriever->exists(uri)) return true; } + return false; } @@ -72,14 +81,29 @@ common::ResourcePtr SampleResourceRetriever::retrieve(const common::Uri& uri) if (!resolveDataUri(uri, relativePath)) return nullptr; - for (const auto& dataPath : mDataDirectories) + if (uri.mAuthority.get() == "sample") { - common::Uri fileUri; - fileUri.fromPath(dataPath + relativePath); + for (const auto& dataPath : mDataDirectories) + { + common::Uri fileUri; + fileUri.fromPath(dataPath + relativePath); + + if(!mLocalRetriever->exists(fileUri)) + continue; - if (const auto resource = mLocalRetriever->retrieve(fileUri)) + if (const auto resource = mLocalRetriever->retrieve(fileUri)) + return resource; + } + } + else + { + if(!mLocalRetriever->exists(uri)) + return nullptr; + + if (const auto resource = mLocalRetriever->retrieve(uri)) return resource; } + return nullptr; } @@ -110,13 +134,6 @@ bool SampleResourceRetriever::resolveDataUri( if (uri.mScheme.get_value_or("file") != "file") return false; - if (uri.mAuthority.get() != "sample") - { - dtwarn << "[SampleResourceRetriever::resolveDataUri] Invalid URI: The " - << "authority of '" << uri.toString() << "' should be 'example'.\n"; - return false; - } - if (!uri.mPath) { dtwarn << "[SampleResourceRetriever::resolveDataUri] Failed extracting" diff --git a/dart/utils/SampleResourceRetriever.hpp b/dart/utils/SampleResourceRetriever.hpp index 54ca89ea0664..4755efb45005 100644 --- a/dart/utils/SampleResourceRetriever.hpp +++ b/dart/utils/SampleResourceRetriever.hpp @@ -86,8 +86,7 @@ class SampleResourceRetriever : public common::ResourceRetriever void addDataDirectory(const std::string& packageDirectory); - bool resolveDataUri(const common::Uri& uri, - std::string& relativePath) const; + bool resolveDataUri(const common::Uri& uri, std::string& relativePath) const; private: common::ResourceRetrieverPtr mLocalRetriever; diff --git a/dart/utils/SkelParser.cpp b/dart/utils/SkelParser.cpp index e7cf747371cc..af3fbb484fc8 100644 --- a/dart/utils/SkelParser.cpp +++ b/dart/utils/SkelParser.cpp @@ -74,7 +74,6 @@ #include "dart/dynamics/Skeleton.hpp" #include "dart/dynamics/Marker.hpp" #include "dart/utils/XmlHelpers.hpp" -#include "dart/utils/CompositeResourceRetriever.hpp" #include "dart/utils/SampleResourceRetriever.hpp" namespace dart { @@ -2408,19 +2407,9 @@ common::ResourceRetrieverPtr getRetriever( const common::ResourceRetrieverPtr& _retriever) { if(_retriever) - { return _retriever; - } else - { - auto newRetriever = std::make_shared(); - newRetriever->addSchemaRetriever( - "file", std::make_shared()); - newRetriever->addSchemaRetriever( - "file", SampleResourceRetriever::create()); - - return newRetriever; - } + return SampleResourceRetriever::create(); } } // anonymous namespace diff --git a/dart/utils/VskParser.cpp b/dart/utils/VskParser.cpp index b01bb6ab4d52..7f4567f62f0e 100644 --- a/dart/utils/VskParser.cpp +++ b/dart/utils/VskParser.cpp @@ -42,7 +42,6 @@ #include "dart/common/LocalResourceRetriever.hpp" #include "dart/common/Uri.hpp" #include "dart/dynamics/dynamics.hpp" -#include "dart/utils/CompositeResourceRetriever.hpp" #include "dart/utils/SampleResourceRetriever.hpp" #include "dart/utils/XmlHelpers.hpp" @@ -1024,19 +1023,9 @@ common::ResourceRetrieverPtr getRetriever( const common::ResourceRetrieverPtr& retriever) { if(retriever) - { return retriever; - } else - { - auto newRetriever = std::make_shared(); - newRetriever->addSchemaRetriever( - "file", std::make_shared()); - newRetriever->addSchemaRetriever( - "file", SampleResourceRetriever::create()); - - return newRetriever; - } + return SampleResourceRetriever::create(); } } // anonymous namespace diff --git a/dart/utils/sdf/SdfParser.cpp b/dart/utils/sdf/SdfParser.cpp index 3a6dffdb5be2..a72e9fd66be7 100644 --- a/dart/utils/sdf/SdfParser.cpp +++ b/dart/utils/sdf/SdfParser.cpp @@ -62,7 +62,6 @@ #include "dart/simulation/World.hpp" #include "dart/utils/SkelParser.hpp" #include "dart/utils/XmlHelpers.hpp" -#include "dart/utils/CompositeResourceRetriever.hpp" #include "dart/utils/SampleResourceRetriever.hpp" namespace dart { @@ -1490,19 +1489,9 @@ common::ResourceRetrieverPtr getRetriever( const common::ResourceRetrieverPtr& retriever) { if(retriever) - { return retriever; - } else - { - auto newRetriever = std::make_shared(); - newRetriever->addSchemaRetriever( - "file", std::make_shared()); - newRetriever->addSchemaRetriever( - "file", SampleResourceRetriever::create()); - - return newRetriever; - } + return SampleResourceRetriever::create(); } } // anonymous namespace From c62c56a7ff1c2999e8fd00beeba9e8f611674a03 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Tue, 31 Jan 2017 00:53:20 -0500 Subject: [PATCH 08/14] Remove existence check before retrieving resource --- dart/utils/CompositeResourceRetriever.cpp | 3 --- dart/utils/SampleResourceRetriever.cpp | 6 ------ 2 files changed, 9 deletions(-) diff --git a/dart/utils/CompositeResourceRetriever.cpp b/dart/utils/CompositeResourceRetriever.cpp index 4d92e1c19870..a83803fb7436 100644 --- a/dart/utils/CompositeResourceRetriever.cpp +++ b/dart/utils/CompositeResourceRetriever.cpp @@ -88,9 +88,6 @@ common::ResourcePtr CompositeResourceRetriever::retrieve( = getRetrievers(_uri); for(const common::ResourceRetrieverPtr& resourceRetriever : retrievers) { - if(!resourceRetriever->exists(_uri)) - continue; - if(common::ResourcePtr resource = resourceRetriever->retrieve(_uri)) return resource; } diff --git a/dart/utils/SampleResourceRetriever.cpp b/dart/utils/SampleResourceRetriever.cpp index 6dcb396fb22f..8a94169bb111 100644 --- a/dart/utils/SampleResourceRetriever.cpp +++ b/dart/utils/SampleResourceRetriever.cpp @@ -88,18 +88,12 @@ common::ResourcePtr SampleResourceRetriever::retrieve(const common::Uri& uri) common::Uri fileUri; fileUri.fromPath(dataPath + relativePath); - if(!mLocalRetriever->exists(fileUri)) - continue; - if (const auto resource = mLocalRetriever->retrieve(fileUri)) return resource; } } else { - if(!mLocalRetriever->exists(uri)) - return nullptr; - if (const auto resource = mLocalRetriever->retrieve(uri)) return resource; } From dd6cbdcba6faad7fd90de4b4de280d9c6ef3598b Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Tue, 31 Jan 2017 21:59:26 -0500 Subject: [PATCH 09/14] Make tutorials directory independent from main build system --- CMakeLists.txt | 13 +++++++++++-- cmake/DARTMacros.cmake | 16 ++++++++++++++++ tutorials/CMakeLists.txt | 33 ++++++++++++--------------------- 3 files changed, 39 insertions(+), 23 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f7efe970ac58..6aa6a8fb72ea 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -296,9 +296,18 @@ if(TINYXML_FOUND AND TINYXML2_FOUND AND BULLET_FOUND) message(STATUS "Adding ${examples_length} examples") endif(DART_VERBOSE) - # Add a "tutorials" target to build tutorials. - add_subdirectory(tutorials EXCLUDE_FROM_ALL) + # Add tutorial targets + dart_get_subdir_list(tutorial_subdirs ${CMAKE_CURRENT_LIST_DIR}/tutorials) + foreach(child ${tutorial_subdirs}) + if(IS_DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/tutorials/${child}") + file(GLOB srcs "${CMAKE_CURRENT_LIST_DIR}/tutorials/${child}/*.cpp") + add_executable(${child} EXCLUDE_FROM_ALL ${srcs}) + target_link_libraries(${child} dart dart-utils-urdf dart-gui) + dart_add_tutorial(${child}) + endif() + endforeach() + # Add a "tutorials" target to build tutorials. get_property(tutorials GLOBAL PROPERTY DART_TUTORIALS) add_custom_target(tutorials DEPENDS ${tutorials}) diff --git a/cmake/DARTMacros.cmake b/cmake/DARTMacros.cmake index 676436600eff..3bc3cb714b2a 100644 --- a/cmake/DARTMacros.cmake +++ b/cmake/DARTMacros.cmake @@ -26,6 +26,22 @@ macro(dart_get_filename_components _var _cacheDesc) endforeach() endmacro() +#=============================================================================== +# Generate directory list of ${curdir} +# Usage: +# dart_get_subdir_list(var curdir) +#=============================================================================== +macro(dart_get_subdir_list var curdir) + file(GLOB children RELATIVE ${curdir} "${curdir}/*") + set(dirlist "") + foreach(child ${children}) + if(IS_DIRECTORY ${curdir}/${child}) + LIST(APPEND dirlist ${child}) + endif() + endforeach() + set(${var} ${dirlist}) +endmacro() + #=============================================================================== # Generate header file list to a cached list. # Usage: diff --git a/tutorials/CMakeLists.txt b/tutorials/CMakeLists.txt index 24507e289050..c8994a908853 100644 --- a/tutorials/CMakeLists.txt +++ b/tutorials/CMakeLists.txt @@ -1,21 +1,12 @@ -# A list of tutorials -set_property(DIRECTORY PROPERTY FOLDER Tutorials) - -# Automatically identify all directories in the tutorials folder -file(GLOB children RELATIVE ${CMAKE_CURRENT_LIST_DIR} "*") -set(directories "") -foreach(child ${children}) - if(IS_DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/${child}") - - file(GLOB srcs "${CMAKE_CURRENT_LIST_DIR}/${child}/*.cpp") - - if(srcs) - add_executable(${child} ${srcs}) - target_link_libraries(${child} dart dart-utils-urdf dart-gui) - dart_add_tutorial(${child}) - else() - add_subdirectory(${child}) - endif() - - endif() -endforeach() +cmake_minimum_required(VERSION 2.8.12) + +project(dart-tutorials) + +add_subdirectory(tutorialBiped) +add_subdirectory(tutorialBiped-Finished) +add_subdirectory(tutorialCollisions) +add_subdirectory(tutorialCollisions-Finished) +add_subdirectory(tutorialDominoes) +add_subdirectory(tutorialDominoes-Finished) +add_subdirectory(tutorialMultiPendulum) +add_subdirectory(tutorialMultiPendulum-Finished) From b490cc6e487f47ac16eddb604943cd2faa953b90 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Wed, 1 Feb 2017 10:25:01 -0500 Subject: [PATCH 10/14] Make examples independent from main build system --- CMakeLists.txt | 63 +++++++++++-------- cmake/DARTMacros.cmake | 35 +++++++++++ examples/CMakeLists.txt | 35 ++++++----- examples/osgExamples/CMakeLists.txt | 32 +++------- .../CMakeLists.txt | 0 .../{osgHubuPuppet => osgHuboPuppet}/README | 0 .../osgHuboPuppet.cpp | 0 tutorials/CMakeLists.txt | 1 + 8 files changed, 100 insertions(+), 66 deletions(-) rename examples/osgExamples/{osgHubuPuppet => osgHuboPuppet}/CMakeLists.txt (100%) rename examples/osgExamples/{osgHubuPuppet => osgHuboPuppet}/README (100%) rename examples/osgExamples/{osgHubuPuppet => osgHuboPuppet}/osgHuboPuppet.cpp (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6aa6a8fb72ea..59c76a947f4a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -250,21 +250,6 @@ if(DART_VERBOSE) message(STATUS "CMAKE_BINARY_DIR : ${CMAKE_BINARY_DIR}") endif(DART_VERBOSE) -#=============================================================================== -# Helper Functions -#=============================================================================== -function(dart_add_example) - dart_property_add(DART_EXAMPLES ${ARGN}) -endfunction(dart_add_example) - -function(dart_add_tutorial) - dart_property_add(DART_TUTORIALS ${ARGN}) -endfunction(dart_add_tutorial) - -function(dart_format_add) - dart_property_add(DART_FORMAT_FILES ${ARGN}) -endfunction() - #=============================================================================== # Add sub-directories #=============================================================================== @@ -279,9 +264,36 @@ if(TINYXML_FOUND AND TINYXML2_FOUND AND BULLET_FOUND) if (OPENGL_FOUND AND HAVE_GLUT) - # Add an "examples" target to build examples. - add_subdirectory(examples EXCLUDE_FROM_ALL) + # Add example targets + dart_add_example(examples/addDeleteSkels dart dart-utils-urdf dart-gui) + dart_add_example(examples/atlasSimbicon dart dart-utils-urdf dart-gui) + dart_add_example(examples/bipedStand dart dart-utils-urdf dart-gui) + dart_add_example(examples/hardcodedDesign dart dart-utils-urdf dart-gui) + dart_add_example(examples/hybridDynamics dart dart-utils-urdf dart-gui) + dart_add_example(examples/jointConstraints dart dart-utils-urdf dart-gui) + dart_add_example(examples/mixedChain dart dart-utils-urdf dart-gui) + dart_add_example(examples/operationalSpaceControl dart dart-utils-urdf dart-gui) + dart_add_example(examples/rigidChain dart dart-utils-urdf dart-gui) + dart_add_example(examples/rigidLoop dart dart-utils-urdf dart-gui) + dart_add_example(examples/rigidShapes dart dart-utils-urdf dart-gui) + dart_add_example(examples/simpleFrames dart dart-utils-urdf dart-gui) + dart_add_example(examples/softBodies dart dart-utils-urdf dart-gui) + dart_add_example(examples/speedTest dart dart-utils-urdf dart-gui) + dart_add_example(examples/vehicle dart dart-utils-urdf dart-gui) + + if(HAVE_OPENSCENEGRAPH) + dart_add_example(examples/osgExamples/osgAtlasPuppet dart dart-utils-urdf dart-gui-osg) + dart_add_example(examples/osgExamples/osgAtlasSimbicon dart dart-utils-urdf dart-gui-osg) + dart_add_example(examples/osgExamples/osgDragAndDrop dart dart-utils-urdf dart-gui-osg) + dart_add_example(examples/osgExamples/osgEmpty dart dart-utils-urdf dart-gui-osg) + dart_add_example(examples/osgExamples/osgHuboPuppet dart dart-utils-urdf dart-gui-osg) + dart_add_example(examples/osgExamples/osgImGui dart dart-utils-urdf dart-gui-osg) + dart_add_example(examples/osgExamples/osgOperationalSpaceControl dart dart-utils-urdf dart-gui-osg) + dart_add_example(examples/osgExamples/osgSoftBodies dart dart-utils-urdf dart-gui-osg) + dart_add_example(examples/osgExamples/osgTinkertoy dart dart-utils-urdf dart-gui-osg) + endif() + # Add an "examples" target to build examples. get_property(examples GLOBAL PROPERTY DART_EXAMPLES) add_custom_target(examples DEPENDS ${examples}) @@ -297,15 +309,14 @@ if(TINYXML_FOUND AND TINYXML2_FOUND AND BULLET_FOUND) endif(DART_VERBOSE) # Add tutorial targets - dart_get_subdir_list(tutorial_subdirs ${CMAKE_CURRENT_LIST_DIR}/tutorials) - foreach(child ${tutorial_subdirs}) - if(IS_DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/tutorials/${child}") - file(GLOB srcs "${CMAKE_CURRENT_LIST_DIR}/tutorials/${child}/*.cpp") - add_executable(${child} EXCLUDE_FROM_ALL ${srcs}) - target_link_libraries(${child} dart dart-utils-urdf dart-gui) - dart_add_tutorial(${child}) - endif() - endforeach() + dart_add_tutorial(tutorials/tutorialBiped dart-utils-urdf dart-gui) + dart_add_tutorial(tutorials/tutorialBiped-Finished dart-utils-urdf dart-gui) + dart_add_tutorial(tutorials/tutorialCollisions dart-utils-urdf dart-gui) + dart_add_tutorial(tutorials/tutorialCollisions-Finished dart-utils-urdf dart-gui) + dart_add_tutorial(tutorials/tutorialDominoes dart-utils-urdf dart-gui) + dart_add_tutorial(tutorials/tutorialDominoes-Finished dart-utils-urdf dart-gui) + dart_add_tutorial(tutorials/tutorialMultiPendulum dart-utils-urdf dart-gui) + dart_add_tutorial(tutorials/tutorialMultiPendulum-Finished dart-utils-urdf dart-gui) # Add a "tutorials" target to build tutorials. get_property(tutorials GLOBAL PROPERTY DART_TUTORIALS) diff --git a/cmake/DARTMacros.cmake b/cmake/DARTMacros.cmake index 3bc3cb714b2a..d3ce97dc2f56 100644 --- a/cmake/DARTMacros.cmake +++ b/cmake/DARTMacros.cmake @@ -120,3 +120,38 @@ function(dart_check_optional_package variable component dependency) return() endif() endfunction() + +#=============================================================================== +function(dart_add_custom_target rel_dir property_name) + set(abs_dir "${CMAKE_CURRENT_LIST_DIR}/${rel_dir}") + + if(NOT IS_DIRECTORY ${abs_dir}) + message(SEND_ERROR "Failed to find directory: ${abs_dir}") + endif() + + # Use the directory name as the executable name + get_filename_component(target_name ${rel_dir} NAME) + + file(GLOB hdrs "${abs_dir}/*.hpp") + file(GLOB srcs "${abs_dir}/*.cpp") + if(srcs) + add_executable(${target_name} EXCLUDE_FROM_ALL ${hdrs} ${srcs}) + target_link_libraries(${target_name} ${ARGN}) + dart_property_add(${property_name} ${target_name}) + endif() +endfunction() + +#=============================================================================== +function(dart_add_example rel_dir) + dart_add_custom_target(${rel_dir} DART_EXAMPLES ${ARGN}) +endfunction() + +#=============================================================================== +function(dart_add_tutorial rel_dir) + dart_add_custom_target(${rel_dir} DART_TUTORIALS ${ARGN}) +endfunction(dart_add_tutorial) + +#=============================================================================== +function(dart_format_add) + dart_property_add(DART_FORMAT_FILES ${ARGN}) +endfunction() diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 550974634417..5d61c128cb6e 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -1,21 +1,22 @@ -# A list of examples -set_property(DIRECTORY PROPERTY FOLDER Examples) +cmake_minimum_required(VERSION 2.8.12) -# Automatically identify all directories in the examples folder -file(GLOB children RELATIVE ${CMAKE_CURRENT_LIST_DIR} "*") -set(directories "") -foreach(child ${children}) - if(IS_DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/${child}") +project(dart-examples) - file(GLOB srcs "${CMAKE_CURRENT_LIST_DIR}/${child}/*.cpp") +add_subdirectory(addDeleteSkels) +add_subdirectory(atlasSimbicon) +add_subdirectory(bipedStand) +add_subdirectory(hardcodedDesign) +add_subdirectory(hybridDynamics) +add_subdirectory(jointConstraints) +add_subdirectory(mixedChain) +add_subdirectory(operationalSpaceControl) +add_subdirectory(rigidChain) +add_subdirectory(rigidLoop) +add_subdirectory(rigidShapes) +add_subdirectory(simpleFrames) +add_subdirectory(softBodies) +add_subdirectory(speedTest) +add_subdirectory(vehicle) - if(srcs) - add_executable(${child} ${srcs}) - target_link_libraries(${child} dart dart-utils-urdf dart-gui) - dart_add_example(${child}) - else() - add_subdirectory(${child}) - endif() +add_subdirectory(osgExamples) - endif() -endforeach() diff --git a/examples/osgExamples/CMakeLists.txt b/examples/osgExamples/CMakeLists.txt index 3258de322970..33f15cdc9fed 100644 --- a/examples/osgExamples/CMakeLists.txt +++ b/examples/osgExamples/CMakeLists.txt @@ -1,23 +1,9 @@ -# This directory depends on OpenSceneGraph -if(HAVE_OPENSCENEGRAPH) - - # Automatically identify all directories in the examples folder - file(GLOB children RELATIVE ${CMAKE_CURRENT_LIST_DIR} "*") - set(directories "") - foreach(child ${children}) - if(IS_DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/${child}") - - file(GLOB srcs "${CMAKE_CURRENT_LIST_DIR}/${child}/*.cpp") - - if(srcs) - add_executable(${child} ${srcs}) - target_link_libraries(${child} dart dart-utils-urdf dart-gui-osg) - dart_add_example(${child}) - else() - add_subdirectory(${child}) - endif() - - endif() - endforeach() - -endif(HAVE_OPENSCENEGRAPH) +add_subdirectory(osgAtlasPuppet) +add_subdirectory(osgAtlasSimbicon) +add_subdirectory(osgDragAndDrop) +add_subdirectory(osgEmpty) +add_subdirectory(osgHuboPuppet) +add_subdirectory(osgImGui) +add_subdirectory(osgOperationalSpaceControl) +add_subdirectory(osgSoftBodies) +add_subdirectory(osgTinkertoy) diff --git a/examples/osgExamples/osgHubuPuppet/CMakeLists.txt b/examples/osgExamples/osgHuboPuppet/CMakeLists.txt similarity index 100% rename from examples/osgExamples/osgHubuPuppet/CMakeLists.txt rename to examples/osgExamples/osgHuboPuppet/CMakeLists.txt diff --git a/examples/osgExamples/osgHubuPuppet/README b/examples/osgExamples/osgHuboPuppet/README similarity index 100% rename from examples/osgExamples/osgHubuPuppet/README rename to examples/osgExamples/osgHuboPuppet/README diff --git a/examples/osgExamples/osgHubuPuppet/osgHuboPuppet.cpp b/examples/osgExamples/osgHuboPuppet/osgHuboPuppet.cpp similarity index 100% rename from examples/osgExamples/osgHubuPuppet/osgHuboPuppet.cpp rename to examples/osgExamples/osgHuboPuppet/osgHuboPuppet.cpp diff --git a/tutorials/CMakeLists.txt b/tutorials/CMakeLists.txt index c8994a908853..e3f47eeb954b 100644 --- a/tutorials/CMakeLists.txt +++ b/tutorials/CMakeLists.txt @@ -10,3 +10,4 @@ add_subdirectory(tutorialDominoes) add_subdirectory(tutorialDominoes-Finished) add_subdirectory(tutorialMultiPendulum) add_subdirectory(tutorialMultiPendulum-Finished) + From 762c693f9befd54ee4bbac15f5ea61d40ed4483d Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Wed, 1 Feb 2017 13:04:23 -0500 Subject: [PATCH 11/14] Add top level README.md for examples and tutorials --- examples/README.md | 35 +++++++++++++++ examples/addDeleteSkels/README | 18 -------- examples/addDeleteSkels/README.md | 20 +++++++++ examples/atlasSimbicon/README | 18 -------- examples/atlasSimbicon/README.md | 20 +++++++++ examples/bipedStand/README | 18 -------- examples/bipedStand/README.md | 20 +++++++++ examples/hardcodedDesign/README | 18 -------- examples/hardcodedDesign/README.md | 22 +++++++++ examples/hardcodedDesign/README.txt | 4 -- examples/hybridDynamics/README | 18 -------- examples/hybridDynamics/README.md | 20 +++++++++ examples/jointConstraints/README | 18 -------- examples/jointConstraints/README.md | 20 +++++++++ examples/mixedChain/README | 18 -------- examples/mixedChain/README.md | 20 +++++++++ examples/operationalSpaceControl/README | 18 -------- examples/operationalSpaceControl/README.md | 20 +++++++++ examples/osgExamples/osgAtlasPuppet/README | 18 -------- examples/osgExamples/osgAtlasPuppet/README.md | 20 +++++++++ examples/osgExamples/osgAtlasSimbicon/README | 18 -------- .../osgExamples/osgAtlasSimbicon/README.md | 20 +++++++++ examples/osgExamples/osgDragAndDrop/README | 18 -------- examples/osgExamples/osgDragAndDrop/README.md | 20 +++++++++ examples/osgExamples/osgEmpty/README | 18 -------- examples/osgExamples/osgEmpty/README.md | 20 +++++++++ examples/osgExamples/osgHuboPuppet/README | 18 -------- examples/osgExamples/osgHuboPuppet/README.md | 20 +++++++++ examples/osgExamples/osgImGui/README | 18 -------- examples/osgExamples/osgImGui/README.md | 20 +++++++++ .../osgOperationalSpaceControl/README | 18 -------- .../osgOperationalSpaceControl/README.md | 20 +++++++++ examples/osgExamples/osgSoftBodies/README | 18 -------- examples/osgExamples/osgSoftBodies/README.md | 20 +++++++++ examples/osgExamples/osgTinkertoy/README | 18 -------- examples/osgExamples/osgTinkertoy/README.md | 20 +++++++++ examples/rigidChain/README | 18 -------- examples/rigidChain/README.md | 20 +++++++++ examples/rigidCubes/README | 18 -------- examples/rigidCubes/README.md | 20 +++++++++ examples/rigidLoop/README | 18 -------- examples/rigidLoop/README.md | 20 +++++++++ examples/rigidShapes/README | 18 -------- examples/rigidShapes/README.md | 20 +++++++++ examples/simpleFrames/README | 18 -------- examples/simpleFrames/README.md | 20 +++++++++ examples/softBodies/README | 18 -------- examples/softBodies/README.md | 20 +++++++++ examples/speedTest/README | 18 -------- examples/speedTest/README.md | 20 +++++++++ examples/vehicle/README | 18 -------- examples/vehicle/README.md | 20 +++++++++ tutorials/CMakeLists.txt | 1 - tutorials/README.md | 45 +++++++++++++++++++ 54 files changed, 582 insertions(+), 455 deletions(-) create mode 100644 examples/README.md delete mode 100644 examples/addDeleteSkels/README create mode 100644 examples/addDeleteSkels/README.md delete mode 100644 examples/atlasSimbicon/README create mode 100644 examples/atlasSimbicon/README.md delete mode 100644 examples/bipedStand/README create mode 100644 examples/bipedStand/README.md delete mode 100644 examples/hardcodedDesign/README create mode 100644 examples/hardcodedDesign/README.md delete mode 100644 examples/hardcodedDesign/README.txt delete mode 100644 examples/hybridDynamics/README create mode 100644 examples/hybridDynamics/README.md delete mode 100644 examples/jointConstraints/README create mode 100644 examples/jointConstraints/README.md delete mode 100644 examples/mixedChain/README create mode 100644 examples/mixedChain/README.md delete mode 100644 examples/operationalSpaceControl/README create mode 100644 examples/operationalSpaceControl/README.md delete mode 100644 examples/osgExamples/osgAtlasPuppet/README create mode 100644 examples/osgExamples/osgAtlasPuppet/README.md delete mode 100644 examples/osgExamples/osgAtlasSimbicon/README create mode 100644 examples/osgExamples/osgAtlasSimbicon/README.md delete mode 100644 examples/osgExamples/osgDragAndDrop/README create mode 100644 examples/osgExamples/osgDragAndDrop/README.md delete mode 100644 examples/osgExamples/osgEmpty/README create mode 100644 examples/osgExamples/osgEmpty/README.md delete mode 100644 examples/osgExamples/osgHuboPuppet/README create mode 100644 examples/osgExamples/osgHuboPuppet/README.md delete mode 100644 examples/osgExamples/osgImGui/README create mode 100644 examples/osgExamples/osgImGui/README.md delete mode 100644 examples/osgExamples/osgOperationalSpaceControl/README create mode 100644 examples/osgExamples/osgOperationalSpaceControl/README.md delete mode 100644 examples/osgExamples/osgSoftBodies/README create mode 100644 examples/osgExamples/osgSoftBodies/README.md delete mode 100644 examples/osgExamples/osgTinkertoy/README create mode 100644 examples/osgExamples/osgTinkertoy/README.md delete mode 100644 examples/rigidChain/README create mode 100644 examples/rigidChain/README.md delete mode 100644 examples/rigidCubes/README create mode 100644 examples/rigidCubes/README.md delete mode 100644 examples/rigidLoop/README create mode 100644 examples/rigidLoop/README.md delete mode 100644 examples/rigidShapes/README create mode 100644 examples/rigidShapes/README.md delete mode 100644 examples/simpleFrames/README create mode 100644 examples/simpleFrames/README.md delete mode 100644 examples/softBodies/README create mode 100644 examples/softBodies/README.md delete mode 100644 examples/speedTest/README create mode 100644 examples/speedTest/README.md delete mode 100644 examples/vehicle/README create mode 100644 examples/vehicle/README.md create mode 100644 tutorials/README.md diff --git a/examples/README.md b/examples/README.md new file mode 100644 index 000000000000..81d9c913016a --- /dev/null +++ b/examples/README.md @@ -0,0 +1,35 @@ +# DART Examples README + +## Build Each Example + +Copy the subdirectory to your workspace and follow the instruction of README.md +in the subdirectory. + +## Build Examples as One Project + +### Build Instructions + +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +Copy this directory to your workspace (e.g., in Linux): + + $ cp -r examples /your/workspace/directory/dart_examples + $ cd /your/workspace/directory/dart_examples + +From the workspace directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +### Execute Instructions + +Launch the each executable from the build directory above (e.g.,): + + $ ./rigidCubes/rigidCubes + +Follow the instructions detailed in the console. + + diff --git a/examples/addDeleteSkels/README b/examples/addDeleteSkels/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/addDeleteSkels/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/addDeleteSkels/README.md b/examples/addDeleteSkels/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/addDeleteSkels/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/atlasSimbicon/README b/examples/atlasSimbicon/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/atlasSimbicon/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/atlasSimbicon/README.md b/examples/atlasSimbicon/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/atlasSimbicon/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/bipedStand/README b/examples/bipedStand/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/bipedStand/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/bipedStand/README.md b/examples/bipedStand/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/bipedStand/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/hardcodedDesign/README b/examples/hardcodedDesign/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/hardcodedDesign/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/hardcodedDesign/README.md b/examples/hardcodedDesign/README.md new file mode 100644 index 000000000000..5360dca4e855 --- /dev/null +++ b/examples/hardcodedDesign/README.md @@ -0,0 +1,22 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +This example shows the construction of a simple dynamic skeleton with three joints. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/hardcodedDesign/README.txt b/examples/hardcodedDesign/README.txt deleted file mode 100644 index cd908d9ac857..000000000000 --- a/examples/hardcodedDesign/README.txt +++ /dev/null @@ -1,4 +0,0 @@ -This example shows the construction of a simple dynamic skeleton with three joints. - -Can Erdogan -Feb 02, 2013 diff --git a/examples/hybridDynamics/README b/examples/hybridDynamics/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/hybridDynamics/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/hybridDynamics/README.md b/examples/hybridDynamics/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/hybridDynamics/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/jointConstraints/README b/examples/jointConstraints/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/jointConstraints/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/jointConstraints/README.md b/examples/jointConstraints/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/jointConstraints/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/mixedChain/README b/examples/mixedChain/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/mixedChain/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/mixedChain/README.md b/examples/mixedChain/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/mixedChain/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/operationalSpaceControl/README b/examples/operationalSpaceControl/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/operationalSpaceControl/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/operationalSpaceControl/README.md b/examples/operationalSpaceControl/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/operationalSpaceControl/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/osgExamples/osgAtlasPuppet/README b/examples/osgExamples/osgAtlasPuppet/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/osgExamples/osgAtlasPuppet/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/osgExamples/osgAtlasPuppet/README.md b/examples/osgExamples/osgAtlasPuppet/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/osgExamples/osgAtlasPuppet/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/osgExamples/osgAtlasSimbicon/README b/examples/osgExamples/osgAtlasSimbicon/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/osgExamples/osgAtlasSimbicon/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/osgExamples/osgAtlasSimbicon/README.md b/examples/osgExamples/osgAtlasSimbicon/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/osgExamples/osgAtlasSimbicon/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/osgExamples/osgDragAndDrop/README b/examples/osgExamples/osgDragAndDrop/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/osgExamples/osgDragAndDrop/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/osgExamples/osgDragAndDrop/README.md b/examples/osgExamples/osgDragAndDrop/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/osgExamples/osgDragAndDrop/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/osgExamples/osgEmpty/README b/examples/osgExamples/osgEmpty/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/osgExamples/osgEmpty/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/osgExamples/osgEmpty/README.md b/examples/osgExamples/osgEmpty/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/osgExamples/osgEmpty/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/osgExamples/osgHuboPuppet/README b/examples/osgExamples/osgHuboPuppet/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/osgExamples/osgHuboPuppet/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/osgExamples/osgHuboPuppet/README.md b/examples/osgExamples/osgHuboPuppet/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/osgExamples/osgHuboPuppet/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/osgExamples/osgImGui/README b/examples/osgExamples/osgImGui/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/osgExamples/osgImGui/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/osgExamples/osgImGui/README.md b/examples/osgExamples/osgImGui/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/osgExamples/osgImGui/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/osgExamples/osgOperationalSpaceControl/README b/examples/osgExamples/osgOperationalSpaceControl/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/osgExamples/osgOperationalSpaceControl/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/osgExamples/osgOperationalSpaceControl/README.md b/examples/osgExamples/osgOperationalSpaceControl/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/osgExamples/osgOperationalSpaceControl/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/osgExamples/osgSoftBodies/README b/examples/osgExamples/osgSoftBodies/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/osgExamples/osgSoftBodies/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/osgExamples/osgSoftBodies/README.md b/examples/osgExamples/osgSoftBodies/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/osgExamples/osgSoftBodies/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/osgExamples/osgTinkertoy/README b/examples/osgExamples/osgTinkertoy/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/osgExamples/osgTinkertoy/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/osgExamples/osgTinkertoy/README.md b/examples/osgExamples/osgTinkertoy/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/osgExamples/osgTinkertoy/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/rigidChain/README b/examples/rigidChain/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/rigidChain/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/rigidChain/README.md b/examples/rigidChain/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/rigidChain/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/rigidCubes/README b/examples/rigidCubes/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/rigidCubes/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/rigidCubes/README.md b/examples/rigidCubes/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/rigidCubes/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/rigidLoop/README b/examples/rigidLoop/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/rigidLoop/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/rigidLoop/README.md b/examples/rigidLoop/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/rigidLoop/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/rigidShapes/README b/examples/rigidShapes/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/rigidShapes/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/rigidShapes/README.md b/examples/rigidShapes/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/rigidShapes/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/simpleFrames/README b/examples/simpleFrames/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/simpleFrames/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/simpleFrames/README.md b/examples/simpleFrames/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/simpleFrames/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/softBodies/README b/examples/softBodies/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/softBodies/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/softBodies/README.md b/examples/softBodies/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/softBodies/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/speedTest/README b/examples/speedTest/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/speedTest/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/speedTest/README.md b/examples/speedTest/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/speedTest/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/examples/vehicle/README b/examples/vehicle/README deleted file mode 100644 index 1e30c89e5fcc..000000000000 --- a/examples/vehicle/README +++ /dev/null @@ -1,18 +0,0 @@ -This project is dependent on DART. Please make sure a proper version of DART is -installed before building this project. - -1. Build Instructions - - * From this directory: - $ mkdir build - $ cd build - $ cmake .. - $ make - -2. Execute Instructions - - * Launch the executable from the build directory above: - $ ./{generated_executable} - - * Follow the instructions detailed in the console. - diff --git a/examples/vehicle/README.md b/examples/vehicle/README.md new file mode 100644 index 000000000000..965b52cdf07b --- /dev/null +++ b/examples/vehicle/README.md @@ -0,0 +1,20 @@ +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +## Build Instructions + +From this directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +## Execute Instructions + +Launch the executable from the build directory above: + + $ ./{generated_executable} + +Follow the instructions detailed in the console. + diff --git a/tutorials/CMakeLists.txt b/tutorials/CMakeLists.txt index e3f47eeb954b..c8994a908853 100644 --- a/tutorials/CMakeLists.txt +++ b/tutorials/CMakeLists.txt @@ -10,4 +10,3 @@ add_subdirectory(tutorialDominoes) add_subdirectory(tutorialDominoes-Finished) add_subdirectory(tutorialMultiPendulum) add_subdirectory(tutorialMultiPendulum-Finished) - diff --git a/tutorials/README.md b/tutorials/README.md new file mode 100644 index 000000000000..25e84b6a28ea --- /dev/null +++ b/tutorials/README.md @@ -0,0 +1,45 @@ +# DART Tutotirals README + +The purpose of this set of tutorials is to provide a quick introduction to +using DART. We designed many hands-on exercises to make the learning +effective and fun. To follow along with this tutorial, first locate +the tutorial code in the directory: +[dart/tutorials](https://github.com/dartsim/dart/blob/master/tutorials). +For each of the four tutorials, we provide the skeleton code as the starting +point (e.g. [tutorialMultiPendulum.cpp] +(https://github.com/dartsim/dart/blob/master/tutorials/ +tutorialMultiPendulum.cpp)) and the final code as the answer to the tutorial +(e.g. [tutorialMultiPendulum-Finished.cpp](https://github.com/dartsim/dart/blob/master/tutorials/tutorialMultiPendulum-Finished.cpp)). + +## Build Each Example + +Copy the subdirectory to your workspace and follow the instruction of README.md +in the subdirectory. + +## Build Examples as One Project + +### Build Instructions + +This project is dependent on DART. Please make sure a proper version of DART is +installed before building this project. + +Copy this directory to your workspace (e.g., in Linux): + + $ cp -r tutorials /your/workspace/directory/dart_tutorials + $ cd /your/workspace/directory/dart_tutorials + +From the workspace directory: + + $ mkdir build + $ cd build + $ cmake .. + $ make + +### Execute Instructions + +Launch the each executable from the build directory above (e.g.,): + + $ ./tutorialBiped/tutorialBiped + +Follow the instructions detailed in the console. + From d3b609ad45fb01c2ae9620c73dddc42bd1f21703 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Wed, 1 Feb 2017 15:11:38 -0500 Subject: [PATCH 12/14] Fix formatting in SdfParser.cpp --- dart/utils/sdf/SdfParser.cpp | 48 +++++++++++++++++++++--------------- 1 file changed, 28 insertions(+), 20 deletions(-) diff --git a/dart/utils/sdf/SdfParser.cpp b/dart/utils/sdf/SdfParser.cpp index a72e9fd66be7..dcdb1e089b93 100644 --- a/dart/utils/sdf/SdfParser.cpp +++ b/dart/utils/sdf/SdfParser.cpp @@ -75,10 +75,10 @@ using BodyPropPtr = std::shared_ptr; struct SDFBodyNode { - BodyPropPtr properties; - Eigen::Isometry3d initTransform; - std::string type; - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + BodyPropPtr properties; + Eigen::Isometry3d initTransform; + std::string type; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; using JointPropPtr = std::shared_ptr; @@ -97,21 +97,25 @@ using BodyMap = Eigen::aligned_map; // Maps a child BodyNode to the properties of its parent Joint using JointMap = std::map; -simulation::WorldPtr readWorld(tinyxml2::XMLElement* worldElement, +simulation::WorldPtr readWorld( + tinyxml2::XMLElement* worldElement, const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever); -void readPhysics(tinyxml2::XMLElement* physicsElement, - simulation::WorldPtr world); +void readPhysics( + tinyxml2::XMLElement* physicsElement, + simulation::WorldPtr world); -dynamics::SkeletonPtr readSkeleton(tinyxml2::XMLElement* skeletonElement, +dynamics::SkeletonPtr readSkeleton( + tinyxml2::XMLElement* skeletonElement, const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever); -bool createPair(dynamics::SkeletonPtr skeleton, - dynamics::BodyNode* parent, - const SDFJoint& newJoint, - const SDFBodyNode& newBody); +bool createPair( + dynamics::SkeletonPtr skeleton, + dynamics::BodyNode* parent, + const SDFJoint& newJoint, + const SDFBodyNode& newBody); enum NextResult { @@ -156,8 +160,8 @@ dynamics::SoftBodyNode::UniqueProperties readSoftBodyProperties( tinyxml2::XMLElement* softBodyNodeElement); dynamics::ShapePtr readShape(tinyxml2::XMLElement* shapelement, - const common::Uri& baseUri, - const common::ResourceRetrieverPtr& retriever); + const common::Uri& baseUri, + const common::ResourceRetrieverPtr& retriever); dynamics::ShapeNode* readShapeNode( dynamics::BodyNode* bodyNode, @@ -171,17 +175,20 @@ void readMaterial( tinyxml2::XMLElement* materialEle, dynamics::ShapeNode* shapeNode); -void readVisualizationShapeNode(dynamics::BodyNode* bodyNode, +void readVisualizationShapeNode( + dynamics::BodyNode* bodyNode, tinyxml2::XMLElement* vizShapeNodeEle, const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever); -void readCollisionShapeNode(dynamics::BodyNode* bodyNode, +void readCollisionShapeNode( + dynamics::BodyNode* bodyNode, tinyxml2::XMLElement* collShapeNodeEle, const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever); -void readAspects(const dynamics::SkeletonPtr& skeleton, +void readAspects( + const dynamics::SkeletonPtr& skeleton, tinyxml2::XMLElement* skeletonElement, const common::Uri& baseUri, const common::ResourceRetrieverPtr& retriever); @@ -191,7 +198,8 @@ JointMap readAllJoints( const Eigen::Isometry3d& skeletonFrame, const BodyMap& sdfBodyNodes); -SDFJoint readJoint(tinyxml2::XMLElement* jointElement, +SDFJoint readJoint( + tinyxml2::XMLElement* jointElement, const BodyMap& bodies, const Eigen::Isometry3d& skeletonFrame); @@ -211,12 +219,12 @@ dynamics::PrismaticJoint::Properties readPrismaticJoint( const std::string& name); dynamics::ScrewJoint::Properties readScrewJoint( - tinyxml2::XMLElement* jointElement, + tinyxml2::XMLElement* jointElement, const Eigen::Isometry3d& parentModelFrame, const std::string& name); dynamics::UniversalJoint::Properties readUniversalJoint( - tinyxml2::XMLElement* jointElement, + tinyxml2::XMLElement* jointElement, const Eigen::Isometry3d& parentModelFrame, const std::string& name); From c89f7073c022281bc8b49f9f7060be6c52a1ba06 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Wed, 1 Feb 2017 15:46:05 -0500 Subject: [PATCH 13/14] Copy whole directories of data, examples, tutorials w/o any modification --- CMakeLists.txt | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 59c76a947f4a..b7e9767bae3e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -412,14 +412,11 @@ install(DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/data" # Examples source install(DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/examples" - DESTINATION ${DART_ADDITIONAL_DOCUMENTATION_INSTALL_PATH} - PATTERN "examples/CMakeLists.txt" EXCLUDE - PATTERN "examples/osgExamples/CMakeLists.txt" EXCLUDE) + DESTINATION ${DART_ADDITIONAL_DOCUMENTATION_INSTALL_PATH}) # Tutorials source install(DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/tutorials" - DESTINATION ${DART_ADDITIONAL_DOCUMENTATION_INSTALL_PATH} - PATTERN "tutorials/CMakeLists.txt" EXCLUDE) + DESTINATION ${DART_ADDITIONAL_DOCUMENTATION_INSTALL_PATH}) #=============================================================================== # Uninstall From 3cbbbc76586f6be8fa878039274413dfc98f761e Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 2 Feb 2017 10:36:08 -0500 Subject: [PATCH 14/14] Change URI pattern of sample data (e.g., dart://sample/skel/shapes.skel) --- ...etriever.cpp => DartResourceRetriever.cpp} | 16 ++-- ...etriever.hpp => DartResourceRetriever.hpp} | 22 +++--- dart/utils/SkelParser.cpp | 15 +++- dart/utils/VskParser.cpp | 17 ++++- dart/utils/sdf/SdfParser.cpp | 17 ++++- dart/utils/urdf/DartLoader.cpp | 4 +- examples/addDeleteSkels/Main.cpp | 2 +- examples/atlasSimbicon/Main.cpp | 4 +- examples/bipedStand/Main.cpp | 2 +- examples/hybridDynamics/Main.cpp | 2 +- examples/jointConstraints/Main.cpp | 2 +- examples/mixedChain/Main.cpp | 2 +- examples/operationalSpaceControl/Main.cpp | 4 +- .../osgAtlasPuppet/osgAtlasPuppet.cpp | 2 +- .../osgExamples/osgAtlasSimbicon/main.cpp | 4 +- .../osgOperationalSpaceControl.cpp | 4 +- .../osgSoftBodies/osgSoftBodies.cpp | 2 +- examples/rigidChain/Main.cpp | 2 +- examples/rigidLoop/Main.cpp | 2 +- examples/rigidShapes/Main.cpp | 2 +- examples/softBodies/Main.cpp | 2 +- examples/speedTest/Main.cpp | 38 +++++----- examples/vehicle/Main.cpp | 2 +- .../tutorialBiped-Finished.cpp | 4 +- tutorials/tutorialBiped/tutorialBiped.cpp | 2 +- .../tutorialDominoes-Finished.cpp | 2 +- unittests/comprehensive/test_Collision.cpp | 2 +- unittests/comprehensive/test_Constraint.cpp | 38 +++++----- unittests/comprehensive/test_Dynamics.cpp | 52 ++++++------- .../comprehensive/test_ForwardKinematics.cpp | 4 +- unittests/comprehensive/test_Joints.cpp | 8 +- unittests/comprehensive/test_Skeleton.cpp | 38 +++++----- unittests/comprehensive/test_SoftDynamics.cpp | 2 +- unittests/comprehensive/test_World.cpp | 76 +++++++++---------- unittests/unit/CMakeLists.txt | 4 +- unittests/unit/test_DartLoader.cpp | 14 ++-- ...ver.cpp => test_DartResourceRetriever.cpp} | 18 ++--- unittests/unit/test_FileInfoWorld.cpp | 2 +- .../unit/test_PackageResourceRetriever.cpp | 68 ++++++++--------- unittests/unit/test_SdfParser.cpp | 20 ++--- unittests/unit/test_SkelParser.cpp | 20 ++--- unittests/unit/test_VskParser.cpp | 8 +- 42 files changed, 292 insertions(+), 259 deletions(-) rename dart/utils/{SampleResourceRetriever.cpp => DartResourceRetriever.cpp} (89%) rename dart/utils/{SampleResourceRetriever.hpp => DartResourceRetriever.hpp} (83%) rename unittests/unit/{test_SampleResourceRetriever.cpp => test_DartResourceRetriever.cpp} (80%) diff --git a/dart/utils/SampleResourceRetriever.cpp b/dart/utils/DartResourceRetriever.cpp similarity index 89% rename from dart/utils/SampleResourceRetriever.cpp rename to dart/utils/DartResourceRetriever.cpp index 8a94169bb111..007fefe6a922 100644 --- a/dart/utils/SampleResourceRetriever.cpp +++ b/dart/utils/DartResourceRetriever.cpp @@ -28,7 +28,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "dart/utils/SampleResourceRetriever.hpp" +#include "dart/utils/DartResourceRetriever.hpp" #include #include @@ -40,7 +40,7 @@ namespace dart { namespace utils { //============================================================================== -SampleResourceRetriever::SampleResourceRetriever() +DartResourceRetriever::DartResourceRetriever() : mLocalRetriever(std::make_shared()) { addDataDirectory(DART_DATA_LOCAL_PATH); @@ -48,7 +48,7 @@ SampleResourceRetriever::SampleResourceRetriever() } //============================================================================== -bool SampleResourceRetriever::exists(const common::Uri& uri) +bool DartResourceRetriever::exists(const common::Uri& uri) { std::string relativePath; if (!resolveDataUri(uri, relativePath)) @@ -75,7 +75,7 @@ bool SampleResourceRetriever::exists(const common::Uri& uri) } //============================================================================== -common::ResourcePtr SampleResourceRetriever::retrieve(const common::Uri& uri) +common::ResourcePtr DartResourceRetriever::retrieve(const common::Uri& uri) { std::string relativePath; if (!resolveDataUri(uri, relativePath)) @@ -102,7 +102,7 @@ common::ResourcePtr SampleResourceRetriever::retrieve(const common::Uri& uri) } //============================================================================== -void SampleResourceRetriever::addDataDirectory( +void DartResourceRetriever::addDataDirectory( const std::string& dataDirectory) { // Strip a trailing slash. @@ -121,16 +121,16 @@ void SampleResourceRetriever::addDataDirectory( } //============================================================================== -bool SampleResourceRetriever::resolveDataUri( +bool DartResourceRetriever::resolveDataUri( const common::Uri& uri, std::string& relativePath) const { - if (uri.mScheme.get_value_or("file") != "file") + if (uri.mScheme.get_value_or("dart") != "dart") return false; if (!uri.mPath) { - dtwarn << "[SampleResourceRetriever::resolveDataUri] Failed extracting" + dtwarn << "[DartResourceRetriever::resolveDataUri] Failed extracting" " relative path from URI '" << uri.toString() << "'.\n"; return false; } diff --git a/dart/utils/SampleResourceRetriever.hpp b/dart/utils/DartResourceRetriever.hpp similarity index 83% rename from dart/utils/SampleResourceRetriever.hpp rename to dart/utils/DartResourceRetriever.hpp index 4755efb45005..71bc8d72dd7e 100644 --- a/dart/utils/SampleResourceRetriever.hpp +++ b/dart/utils/DartResourceRetriever.hpp @@ -28,8 +28,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef DART_UTILS_SAMPLERESOURCERETRIEVER_HPP_ -#define DART_UTILS_SAMPLERESOURCERETRIEVER_HPP_ +#ifndef DART_UTILS_DARTRESOURCERETRIEVER_HPP_ +#define DART_UTILS_DARTRESOURCERETRIEVER_HPP_ #include #include @@ -44,14 +44,14 @@ namespace utils { /// /// Example of a sample data URI: /// @code -/// "file://sample/skel/shapes.skel" +/// "dart://sample/skel/shapes.skel" /// \______________/ /// | /// file path with respect to /// the sample data directory /// @endcode /// -/// SampleResourceRetriever searches files in the following order: +/// DartResourceRetriever searches files in the following order: /// 1) DART_DATA_LOCAL_PATH: path to the data directory in source /// (e.g., [DART_SRC_ROOT]/data/). /// 2) DART_DATA_GLOBAL_PATH: path to the data directory installed at a system @@ -60,21 +60,21 @@ namespace utils { /// where DART_DATA_LOCAL_PATH and DART_DATA_GLOBAL_PATH are defined in /// config.hpp that are determined in CMake time. /// -class SampleResourceRetriever : public common::ResourceRetriever +class DartResourceRetriever : public common::ResourceRetriever { public: template - static std::shared_ptr create(Args&&... args) + static std::shared_ptr create(Args&&... args) { - return std::make_shared( + return std::make_shared( std::forward(args)...); } /// Constructor. - SampleResourceRetriever(); + DartResourceRetriever(); /// Destructor. - virtual ~SampleResourceRetriever() = default; + virtual ~DartResourceRetriever() = default; // Documentation inherited. bool exists(const common::Uri& uri) override; @@ -94,9 +94,9 @@ class SampleResourceRetriever : public common::ResourceRetriever std::vector mDataDirectories; }; -using SampleResourceRetrieverPtr = std::shared_ptr; +using DartResourceRetrieverPtr = std::shared_ptr; } // namespace utils } // namespace dart -#endif // ifndef DART_UTILS_SAMPLERESOURCERETRIEVER_HPP_ +#endif // ifndef DART_UTILS_DARTRESOURCERETRIEVER_HPP_ diff --git a/dart/utils/SkelParser.cpp b/dart/utils/SkelParser.cpp index af3fbb484fc8..cf96af8b8834 100644 --- a/dart/utils/SkelParser.cpp +++ b/dart/utils/SkelParser.cpp @@ -74,7 +74,8 @@ #include "dart/dynamics/Skeleton.hpp" #include "dart/dynamics/Marker.hpp" #include "dart/utils/XmlHelpers.hpp" -#include "dart/utils/SampleResourceRetriever.hpp" +#include "dart/utils/CompositeResourceRetriever.hpp" +#include "dart/utils/DartResourceRetriever.hpp" namespace dart { namespace utils { @@ -2407,9 +2408,19 @@ common::ResourceRetrieverPtr getRetriever( const common::ResourceRetrieverPtr& _retriever) { if(_retriever) + { return _retriever; + } else - return SampleResourceRetriever::create(); + { + auto newRetriever = std::make_shared(); + newRetriever->addSchemaRetriever( + "file", std::make_shared()); + newRetriever->addSchemaRetriever( + "dart", DartResourceRetriever::create()); + + return DartResourceRetriever::create(); + } } } // anonymous namespace diff --git a/dart/utils/VskParser.cpp b/dart/utils/VskParser.cpp index 7f4567f62f0e..5afebcb0c1c1 100644 --- a/dart/utils/VskParser.cpp +++ b/dart/utils/VskParser.cpp @@ -42,7 +42,8 @@ #include "dart/common/LocalResourceRetriever.hpp" #include "dart/common/Uri.hpp" #include "dart/dynamics/dynamics.hpp" -#include "dart/utils/SampleResourceRetriever.hpp" +#include "dart/utils/CompositeResourceRetriever.hpp" +#include "dart/utils/DartResourceRetriever.hpp" #include "dart/utils/XmlHelpers.hpp" #define SCALE_VSK 1.0e-3 @@ -1022,10 +1023,20 @@ void tokenize(const std::string& str, common::ResourceRetrieverPtr getRetriever( const common::ResourceRetrieverPtr& retriever) { - if(retriever) + if (retriever) + { return retriever; + } else - return SampleResourceRetriever::create(); + { + auto newRetriever = std::make_shared(); + newRetriever->addSchemaRetriever( + "file", std::make_shared()); + newRetriever->addSchemaRetriever( + "dart", DartResourceRetriever::create()); + + return DartResourceRetriever::create(); + } } } // anonymous namespace diff --git a/dart/utils/sdf/SdfParser.cpp b/dart/utils/sdf/SdfParser.cpp index dcdb1e089b93..83c9d0bd9e40 100644 --- a/dart/utils/sdf/SdfParser.cpp +++ b/dart/utils/sdf/SdfParser.cpp @@ -62,7 +62,8 @@ #include "dart/simulation/World.hpp" #include "dart/utils/SkelParser.hpp" #include "dart/utils/XmlHelpers.hpp" -#include "dart/utils/SampleResourceRetriever.hpp" +#include "dart/utils/CompositeResourceRetriever.hpp" +#include "dart/utils/DartResourceRetriever.hpp" namespace dart { namespace utils { @@ -1496,10 +1497,20 @@ dynamics::BallJoint::Properties readBallJoint( common::ResourceRetrieverPtr getRetriever( const common::ResourceRetrieverPtr& retriever) { - if(retriever) + if (retriever) + { return retriever; + } else - return SampleResourceRetriever::create(); + { + auto newRetriever = std::make_shared(); + newRetriever->addSchemaRetriever( + "file", std::make_shared()); + newRetriever->addSchemaRetriever( + "dart", DartResourceRetriever::create()); + + return DartResourceRetriever::create(); + } } } // anonymous namespace diff --git a/dart/utils/urdf/DartLoader.cpp b/dart/utils/urdf/DartLoader.cpp index 0e17ec89aa69..6007f12a1024 100644 --- a/dart/utils/urdf/DartLoader.cpp +++ b/dart/utils/urdf/DartLoader.cpp @@ -52,7 +52,7 @@ #include "dart/dynamics/CylinderShape.hpp" #include "dart/dynamics/MeshShape.hpp" #include "dart/simulation/World.hpp" -#include "dart/utils/SampleResourceRetriever.hpp" +#include "dart/utils/DartResourceRetriever.hpp" #include "dart/utils/urdf/URDFTypes.hpp" #include "dart/utils/urdf/urdf_world_parser.hpp" @@ -68,7 +68,7 @@ DartLoader::DartLoader() { mRetriever->addSchemaRetriever("file", mLocalRetriever); mRetriever->addSchemaRetriever("package", mPackageRetriever); - mRetriever->addSchemaRetriever("file", SampleResourceRetriever::create()); + mRetriever->addSchemaRetriever("dart", DartResourceRetriever::create()); } void DartLoader::addPackageDirectory(const std::string& _packageName, diff --git a/examples/addDeleteSkels/Main.cpp b/examples/addDeleteSkels/Main.cpp index cd89dadf5039..b377cf26b3f6 100644 --- a/examples/addDeleteSkels/Main.cpp +++ b/examples/addDeleteSkels/Main.cpp @@ -38,7 +38,7 @@ int main(int argc, char* argv[]) { // create and initialize the world dart::simulation::WorldPtr myWorld - = dart::utils::SkelParser::readWorld("file://sample/skel/ground.skel"); + = dart::utils::SkelParser::readWorld("dart://sample/skel/ground.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); myWorld->setGravity(gravity); diff --git a/examples/atlasSimbicon/Main.cpp b/examples/atlasSimbicon/Main.cpp index 17672c5ca22e..71b1e803d35d 100644 --- a/examples/atlasSimbicon/Main.cpp +++ b/examples/atlasSimbicon/Main.cpp @@ -52,9 +52,9 @@ int main(int argc, char* argv[]) // Load ground and Atlas robot and add them to the world DartLoader urdfLoader; SkeletonPtr ground = urdfLoader.parseSkeleton( - "file://sample/sdf/atlas/ground.urdf"); + "dart://sample/sdf/atlas/ground.urdf"); SkeletonPtr atlas = SdfParser::readSkeleton( - "file://sample/sdf/atlas/atlas_v3_no_head_soft_feet.sdf"); + "dart://sample/sdf/atlas/atlas_v3_no_head_soft_feet.sdf"); myWorld->addSkeleton(atlas); myWorld->addSkeleton(ground); diff --git a/examples/bipedStand/Main.cpp b/examples/bipedStand/Main.cpp index 86e833630d1a..0cdf6673de5d 100644 --- a/examples/bipedStand/Main.cpp +++ b/examples/bipedStand/Main.cpp @@ -39,7 +39,7 @@ int main(int argc, char* argv[]) { // create and initialize the world dart::simulation::WorldPtr myWorld - = dart::utils::SkelParser::readWorld("file://sample/skel/fullbody1.skel"); + = dart::utils::SkelParser::readWorld("dart://sample/skel/fullbody1.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); diff --git a/examples/hybridDynamics/Main.cpp b/examples/hybridDynamics/Main.cpp index 5048e42f24d7..eaf7dc062a40 100644 --- a/examples/hybridDynamics/Main.cpp +++ b/examples/hybridDynamics/Main.cpp @@ -38,7 +38,7 @@ int main(int argc, char* argv[]) // create and initialize the world dart::simulation::WorldPtr myWorld = dart::utils::SkelParser::readWorld( - "file://sample/skel/fullbody1.skel"); + "dart://sample/skel/fullbody1.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); myWorld->setGravity(gravity); diff --git a/examples/jointConstraints/Main.cpp b/examples/jointConstraints/Main.cpp index 8a87fc9348cf..794f81e6436d 100644 --- a/examples/jointConstraints/Main.cpp +++ b/examples/jointConstraints/Main.cpp @@ -45,7 +45,7 @@ int main(int argc, char* argv[]) // load a skeleton file // create and initialize the world dart::simulation::WorldPtr myWorld - = utils::SkelParser::readWorld("file://sample/skel/fullbody1.skel"); + = utils::SkelParser::readWorld("dart://sample/skel/fullbody1.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); diff --git a/examples/mixedChain/Main.cpp b/examples/mixedChain/Main.cpp index cfbeec03b228..b01ec83143ae 100644 --- a/examples/mixedChain/Main.cpp +++ b/examples/mixedChain/Main.cpp @@ -47,7 +47,7 @@ int main(int argc, char* argv[]) // create and initialize the world dart::simulation::WorldPtr myWorld = dart::utils::SkelParser::readWorld( - "file://sample/skel/test/test_articulated_bodies_10bodies.skel"); + "dart://sample/skel/test/test_articulated_bodies_10bodies.skel"); assert(myWorld != nullptr); int dof = myWorld->getSkeleton(1)->getNumDofs(); diff --git a/examples/operationalSpaceControl/Main.cpp b/examples/operationalSpaceControl/Main.cpp index 48f4fd4da088..9706d4fb109f 100644 --- a/examples/operationalSpaceControl/Main.cpp +++ b/examples/operationalSpaceControl/Main.cpp @@ -42,9 +42,9 @@ int main(int argc, char* argv[]) // load skeletons dart::utils::DartLoader dl; dart::dynamics::SkeletonPtr ground - = dl.parseSkeleton("file://sample/urdf/KR5/ground.urdf"); + = dl.parseSkeleton("dart://sample/urdf/KR5/ground.urdf"); dart::dynamics::SkeletonPtr robot - = dl.parseSkeleton("file://sample/urdf/KR5/KR5 sixx R650.urdf"); + = dl.parseSkeleton("dart://sample/urdf/KR5/KR5 sixx R650.urdf"); world->addSkeleton(ground); world->addSkeleton(robot); diff --git a/examples/osgExamples/osgAtlasPuppet/osgAtlasPuppet.cpp b/examples/osgExamples/osgAtlasPuppet/osgAtlasPuppet.cpp index 961b026b961e..fd71b18daa7b 100644 --- a/examples/osgExamples/osgAtlasPuppet/osgAtlasPuppet.cpp +++ b/examples/osgExamples/osgAtlasPuppet/osgAtlasPuppet.cpp @@ -511,7 +511,7 @@ SkeletonPtr createAtlas() // Parse in the atlas model DartLoader urdf; SkeletonPtr atlas = - urdf.parseSkeleton("file://sample/sdf/atlas/atlas_v3_no_head.urdf"); + urdf.parseSkeleton("dart://sample/sdf/atlas/atlas_v3_no_head.urdf"); // Add a box to the root node to make it easier to click and drag double scale = 0.25; diff --git a/examples/osgExamples/osgAtlasSimbicon/main.cpp b/examples/osgExamples/osgAtlasSimbicon/main.cpp index f6fa5bec66f9..912cbbcaf303 100644 --- a/examples/osgExamples/osgAtlasSimbicon/main.cpp +++ b/examples/osgExamples/osgAtlasSimbicon/main.cpp @@ -44,9 +44,9 @@ int main() // Load ground and Atlas robot and add them to the world dart::utils::DartLoader urdfLoader; - auto ground = urdfLoader.parseSkeleton("file://sample/sdf/atlas/ground.urdf"); + auto ground = urdfLoader.parseSkeleton("dart://sample/sdf/atlas/ground.urdf"); auto atlas = dart::utils::SdfParser::readSkeleton( - "file://sample/sdf/atlas/atlas_v3_no_head.sdf"); + "dart://sample/sdf/atlas/atlas_v3_no_head.sdf"); world->addSkeleton(ground); world->addSkeleton(atlas); diff --git a/examples/osgExamples/osgOperationalSpaceControl/osgOperationalSpaceControl.cpp b/examples/osgExamples/osgOperationalSpaceControl/osgOperationalSpaceControl.cpp index 85748e618c46..b4a08500e6c0 100644 --- a/examples/osgExamples/osgOperationalSpaceControl/osgOperationalSpaceControl.cpp +++ b/examples/osgExamples/osgOperationalSpaceControl/osgOperationalSpaceControl.cpp @@ -253,7 +253,7 @@ int main() // Load the robot dart::dynamics::SkeletonPtr robot = - loader.parseSkeleton("file://sample/urdf/KR5/KR5 sixx R650.urdf"); + loader.parseSkeleton("dart://sample/urdf/KR5/KR5 sixx R650.urdf"); world->addSkeleton(robot); // Set the colors of the models to obey the shape's color specification @@ -275,7 +275,7 @@ int main() // Load the ground dart::dynamics::SkeletonPtr ground = - loader.parseSkeleton("file://sample/urdf/KR5/ground.urdf"); + loader.parseSkeleton("dart://sample/urdf/KR5/ground.urdf"); world->addSkeleton(ground); // Rotate and move the ground so that z is upwards diff --git a/examples/osgExamples/osgSoftBodies/osgSoftBodies.cpp b/examples/osgExamples/osgSoftBodies/osgSoftBodies.cpp index b72538f0aab2..c3595e66b286 100644 --- a/examples/osgExamples/osgSoftBodies/osgSoftBodies.cpp +++ b/examples/osgExamples/osgSoftBodies/osgSoftBodies.cpp @@ -212,7 +212,7 @@ int main() using namespace dart::dynamics; dart::simulation::WorldPtr world = - dart::utils::SkelParser::readWorld("file://sample/skel/softBodies.skel"); + dart::utils::SkelParser::readWorld("dart://sample/skel/softBodies.skel"); osg::ref_ptr node = new RecordingWorld(world); diff --git a/examples/rigidChain/Main.cpp b/examples/rigidChain/Main.cpp index 682e73950ff2..bf185f569f87 100644 --- a/examples/rigidChain/Main.cpp +++ b/examples/rigidChain/Main.cpp @@ -36,7 +36,7 @@ int main(int argc, char* argv[]) { // create and initialize the world dart::simulation::WorldPtr myWorld - = dart::utils::SkelParser::readWorld("file://sample/skel/chain.skel"); + = dart::utils::SkelParser::readWorld("dart://sample/skel/chain.skel"); assert(myWorld != nullptr); // create and initialize the world diff --git a/examples/rigidLoop/Main.cpp b/examples/rigidLoop/Main.cpp index 6f9ca21bb5e3..4151dc0d1a29 100644 --- a/examples/rigidLoop/Main.cpp +++ b/examples/rigidLoop/Main.cpp @@ -44,7 +44,7 @@ int main(int argc, char* argv[]) // load a skeleton file // create and initialize the world dart::simulation::WorldPtr myWorld - = utils::SkelParser::readWorld("file://sample/skel/chain.skel"); + = utils::SkelParser::readWorld("dart://sample/skel/chain.skel"); assert(myWorld != nullptr); // create and initialize the world diff --git a/examples/rigidShapes/Main.cpp b/examples/rigidShapes/Main.cpp index 8cec9f80427f..e477e5bffa91 100644 --- a/examples/rigidShapes/Main.cpp +++ b/examples/rigidShapes/Main.cpp @@ -46,7 +46,7 @@ int main(int argc, char* argv[]) // load a skeleton file // create and initialize the world dart::simulation::WorldPtr myWorld - = dart::utils::SkelParser::readWorld("file://sample/skel/shapes.skel"); + = dart::utils::SkelParser::readWorld("dart://sample/skel/shapes.skel"); assert(myWorld != NULL); // create a window and link it to the world diff --git a/examples/softBodies/Main.cpp b/examples/softBodies/Main.cpp index 120b6f41ef33..2da3b03a4c3f 100644 --- a/examples/softBodies/Main.cpp +++ b/examples/softBodies/Main.cpp @@ -47,7 +47,7 @@ int main(int argc, char* argv[]) // create and initialize the world dart::simulation::WorldPtr myWorld = dart::utils::SkelParser::readWorld( - "file://sample/skel/softBodies.skel"); + "dart://sample/skel/softBodies.skel"); assert(myWorld != nullptr); for(std::size_t i=0; igetNumSkeletons(); ++i) diff --git a/examples/speedTest/Main.cpp b/examples/speedTest/Main.cpp index 01845f4cafa9..d7cb0f210d8b 100644 --- a/examples/speedTest/Main.cpp +++ b/examples/speedTest/Main.cpp @@ -164,25 +164,25 @@ void print_results(const std::vector& result) std::vector getSceneFiles() { std::vector scenes; - scenes.push_back("file://sample/skel/test/chainwhipa.skel"); - scenes.push_back("file://sample/skel/test/single_pendulum.skel"); - scenes.push_back("file://sample/skel/test/single_pendulum_euler_joint.skel"); - scenes.push_back("file://sample/skel/test/single_pendulum_ball_joint.skel"); - scenes.push_back("file://sample/skel/test/double_pendulum.skel"); - scenes.push_back("file://sample/skel/test/double_pendulum_euler_joint.skel"); - scenes.push_back("file://sample/skel/test/double_pendulum_ball_joint.skel"); - scenes.push_back("file://sample/skel/test/serial_chain_revolute_joint.skel"); - scenes.push_back("file://sample/skel/test/serial_chain_eulerxyz_joint.skel"); - scenes.push_back("file://sample/skel/test/serial_chain_ball_joint.skel"); - scenes.push_back("file://sample/skel/test/serial_chain_ball_joint_20.skel"); - scenes.push_back("file://sample/skel/test/serial_chain_ball_joint_40.skel"); - scenes.push_back("file://sample/skel/test/simple_tree_structure.skel"); - scenes.push_back("file://sample/skel/test/simple_tree_structure_euler_joint.skel"); - scenes.push_back("file://sample/skel/test/simple_tree_structure_ball_joint.skel"); - scenes.push_back("file://sample/skel/test/tree_structure.skel"); - scenes.push_back("file://sample/skel/test/tree_structure_euler_joint.skel"); - scenes.push_back("file://sample/skel/test/tree_structure_ball_joint.skel"); - scenes.push_back("file://sample/skel/fullbody1.skel"); + scenes.push_back("dart://sample/skel/test/chainwhipa.skel"); + scenes.push_back("dart://sample/skel/test/single_pendulum.skel"); + scenes.push_back("dart://sample/skel/test/single_pendulum_euler_joint.skel"); + scenes.push_back("dart://sample/skel/test/single_pendulum_ball_joint.skel"); + scenes.push_back("dart://sample/skel/test/double_pendulum.skel"); + scenes.push_back("dart://sample/skel/test/double_pendulum_euler_joint.skel"); + scenes.push_back("dart://sample/skel/test/double_pendulum_ball_joint.skel"); + scenes.push_back("dart://sample/skel/test/serial_chain_revolute_joint.skel"); + scenes.push_back("dart://sample/skel/test/serial_chain_eulerxyz_joint.skel"); + scenes.push_back("dart://sample/skel/test/serial_chain_ball_joint.skel"); + scenes.push_back("dart://sample/skel/test/serial_chain_ball_joint_20.skel"); + scenes.push_back("dart://sample/skel/test/serial_chain_ball_joint_40.skel"); + scenes.push_back("dart://sample/skel/test/simple_tree_structure.skel"); + scenes.push_back("dart://sample/skel/test/simple_tree_structure_euler_joint.skel"); + scenes.push_back("dart://sample/skel/test/simple_tree_structure_ball_joint.skel"); + scenes.push_back("dart://sample/skel/test/tree_structure.skel"); + scenes.push_back("dart://sample/skel/test/tree_structure_euler_joint.skel"); + scenes.push_back("dart://sample/skel/test/tree_structure_ball_joint.skel"); + scenes.push_back("dart://sample/skel/fullbody1.skel"); return scenes; } diff --git a/examples/vehicle/Main.cpp b/examples/vehicle/Main.cpp index 984c2293b3a1..066b879b7640 100644 --- a/examples/vehicle/Main.cpp +++ b/examples/vehicle/Main.cpp @@ -43,7 +43,7 @@ int main(int argc, char* argv[]) using namespace utils; // create and initialize the world - WorldPtr myWorld = SkelParser::readWorld("file://sample/skel/vehicle.skel"); + WorldPtr myWorld = SkelParser::readWorld("dart://sample/skel/vehicle.skel"); assert(myWorld != nullptr); Eigen::Vector3d gravity(0.0, -9.81, 0.0); myWorld->setGravity(gravity); diff --git a/tutorials/tutorialBiped-Finished/tutorialBiped-Finished.cpp b/tutorials/tutorialBiped-Finished/tutorialBiped-Finished.cpp index 8baefbd68742..6ba33f5b9989 100644 --- a/tutorials/tutorialBiped-Finished/tutorialBiped-Finished.cpp +++ b/tutorials/tutorialBiped-Finished/tutorialBiped-Finished.cpp @@ -299,7 +299,7 @@ class MyWindow : public SimWindow SkeletonPtr loadBiped() { // Create the world with a skeleton - WorldPtr world = SkelParser::readWorld("file://sample/skel/biped.skel"); + WorldPtr world = SkelParser::readWorld("dart://sample/skel/biped.skel"); assert(world != nullptr); SkeletonPtr biped = world->getSkeleton("biped"); @@ -337,7 +337,7 @@ void setInitialPose(SkeletonPtr biped) void modifyBipedWithSkateboard(SkeletonPtr biped) { // Load the Skeleton from a file - WorldPtr world = SkelParser::readWorld("file://sample/skel/skateboard.skel"); + WorldPtr world = SkelParser::readWorld("dart://sample/skel/skateboard.skel"); SkeletonPtr skateboard = world->getSkeleton(0); diff --git a/tutorials/tutorialBiped/tutorialBiped.cpp b/tutorials/tutorialBiped/tutorialBiped.cpp index 1432dd012c75..6f98acc20580 100644 --- a/tutorials/tutorialBiped/tutorialBiped.cpp +++ b/tutorials/tutorialBiped/tutorialBiped.cpp @@ -234,7 +234,7 @@ SkeletonPtr loadBiped() // Lesson 1 // Create the world with a skeleton - WorldPtr world = SkelParser::readWorld("file://sample/skel/biped.skel"); + WorldPtr world = SkelParser::readWorld("dart://sample/skel/biped.skel"); assert(world != nullptr); SkeletonPtr biped = world->getSkeleton("biped"); diff --git a/tutorials/tutorialDominoes-Finished/tutorialDominoes-Finished.cpp b/tutorials/tutorialDominoes-Finished/tutorialDominoes-Finished.cpp index 6ffc9c8b7f73..50173541a46f 100644 --- a/tutorials/tutorialDominoes-Finished/tutorialDominoes-Finished.cpp +++ b/tutorials/tutorialDominoes-Finished/tutorialDominoes-Finished.cpp @@ -467,7 +467,7 @@ SkeletonPtr createManipulator() // Load the Skeleton from a file dart::utils::DartLoader loader; SkeletonPtr manipulator = - loader.parseSkeleton("file://sample/urdf/KR5/KR5 sixx R650.urdf"); + loader.parseSkeleton("dart://sample/urdf/KR5/KR5 sixx R650.urdf"); manipulator->setName("manipulator"); // Position its base in a reasonable way diff --git a/unittests/comprehensive/test_Collision.cpp b/unittests/comprehensive/test_Collision.cpp index 5dfa9d4c1fac..d6b978e25c87 100644 --- a/unittests/comprehensive/test_Collision.cpp +++ b/unittests/comprehensive/test_Collision.cpp @@ -1107,7 +1107,7 @@ TEST_F(COLLISION, CollisionOfPrescribedJoints) // Load world and skeleton WorldPtr world = SkelParser::readWorld( - "file://sample/skel/test/collision_of_prescribed_joints_test.skel"); + "dart://sample/skel/test/collision_of_prescribed_joints_test.skel"); world->setTimeStep(timeStep); EXPECT_TRUE(world != nullptr); EXPECT_NEAR(world->getTimeStep(), timeStep, tol); diff --git a/unittests/comprehensive/test_Constraint.cpp b/unittests/comprehensive/test_Constraint.cpp index d27df2a906da..40382a549c04 100644 --- a/unittests/comprehensive/test_Constraint.cpp +++ b/unittests/comprehensive/test_Constraint.cpp @@ -66,25 +66,25 @@ class ConstraintTest : public ::testing::Test //============================================================================== void ConstraintTest::SetUp() { - list.push_back("file://sample/skel/test/chainwhipa.skel"); - list.push_back("file://sample/skel/test/single_pendulum.skel"); - list.push_back("file://sample/skel/test/single_pendulum_euler_joint.skel"); - list.push_back("file://sample/skel/test/single_pendulum_ball_joint.skel"); - list.push_back("file://sample/skel/test/double_pendulum.skel"); - list.push_back("file://sample/skel/test/double_pendulum_euler_joint.skel"); - list.push_back("file://sample/skel/test/double_pendulum_ball_joint.skel"); - list.push_back("file://sample/skel/test/serial_chain_revolute_joint.skel"); - list.push_back("file://sample/skel/test/serial_chain_eulerxyz_joint.skel"); - list.push_back("file://sample/skel/test/serial_chain_ball_joint.skel"); - list.push_back("file://sample/skel/test/serial_chain_ball_joint_20.skel"); - list.push_back("file://sample/skel/test/serial_chain_ball_joint_40.skel"); - list.push_back("file://sample/skel/test/simple_tree_structure.skel"); - list.push_back("file://sample/skel/test/simple_tree_structure_euler_joint.skel"); - list.push_back("file://sample/skel/test/simple_tree_structure_ball_joint.skel"); - list.push_back("file://sample/skel/test/tree_structure.skel"); - list.push_back("file://sample/skel/test/tree_structure_euler_joint.skel"); - list.push_back("file://sample/skel/test/tree_structure_ball_joint.skel"); - list.push_back("file://sample/skel/fullbody1.skel"); + list.push_back("dart://sample/skel/test/chainwhipa.skel"); + list.push_back("dart://sample/skel/test/single_pendulum.skel"); + list.push_back("dart://sample/skel/test/single_pendulum_euler_joint.skel"); + list.push_back("dart://sample/skel/test/single_pendulum_ball_joint.skel"); + list.push_back("dart://sample/skel/test/double_pendulum.skel"); + list.push_back("dart://sample/skel/test/double_pendulum_euler_joint.skel"); + list.push_back("dart://sample/skel/test/double_pendulum_ball_joint.skel"); + list.push_back("dart://sample/skel/test/serial_chain_revolute_joint.skel"); + list.push_back("dart://sample/skel/test/serial_chain_eulerxyz_joint.skel"); + list.push_back("dart://sample/skel/test/serial_chain_ball_joint.skel"); + list.push_back("dart://sample/skel/test/serial_chain_ball_joint_20.skel"); + list.push_back("dart://sample/skel/test/serial_chain_ball_joint_40.skel"); + list.push_back("dart://sample/skel/test/simple_tree_structure.skel"); + list.push_back("dart://sample/skel/test/simple_tree_structure_euler_joint.skel"); + list.push_back("dart://sample/skel/test/simple_tree_structure_ball_joint.skel"); + list.push_back("dart://sample/skel/test/tree_structure.skel"); + list.push_back("dart://sample/skel/test/tree_structure_euler_joint.skel"); + list.push_back("dart://sample/skel/test/tree_structure_ball_joint.skel"); + list.push_back("dart://sample/skel/fullbody1.skel"); } //============================================================================== diff --git a/unittests/comprehensive/test_Dynamics.cpp b/unittests/comprehensive/test_Dynamics.cpp index 855863b8b342..6dd9faa66e0c 100644 --- a/unittests/comprehensive/test_Dynamics.cpp +++ b/unittests/comprehensive/test_Dynamics.cpp @@ -120,25 +120,25 @@ class DynamicsTest : public ::testing::Test void DynamicsTest::SetUp() { // Create a list of skel files to test with - fileList.push_back("file://sample/skel/test/chainwhipa.skel"); - fileList.push_back("file://sample/skel/test/single_pendulum.skel"); - fileList.push_back("file://sample/skel/test/single_pendulum_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/single_pendulum_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/double_pendulum.skel"); - fileList.push_back("file://sample/skel/test/double_pendulum_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/double_pendulum_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_revolute_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_eulerxyz_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_20.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_40.skel"); - fileList.push_back("file://sample/skel/test/simple_tree_structure.skel"); - fileList.push_back("file://sample/skel/test/simple_tree_structure_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/simple_tree_structure_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/tree_structure.skel"); - fileList.push_back("file://sample/skel/test/tree_structure_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/tree_structure_ball_joint.skel"); - fileList.push_back("file://sample/skel/fullbody1.skel"); + fileList.push_back("dart://sample/skel/test/chainwhipa.skel"); + fileList.push_back("dart://sample/skel/test/single_pendulum.skel"); + fileList.push_back("dart://sample/skel/test/single_pendulum_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/single_pendulum_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/double_pendulum.skel"); + fileList.push_back("dart://sample/skel/test/double_pendulum_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/double_pendulum_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_revolute_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_eulerxyz_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_ball_joint_20.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_ball_joint_40.skel"); + fileList.push_back("dart://sample/skel/test/simple_tree_structure.skel"); + fileList.push_back("dart://sample/skel/test/simple_tree_structure_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/simple_tree_structure_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/tree_structure.skel"); + fileList.push_back("dart://sample/skel/test/tree_structure_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/tree_structure_ball_joint.skel"); + fileList.push_back("dart://sample/skel/fullbody1.skel"); // Create a list of reference frames to use during tests refFrames.push_back(new SimpleFrame(Frame::World(), "refFrame1")); @@ -1954,12 +1954,12 @@ TEST_F(DynamicsTest, compareEquationsOfMotion) // TODO(JS): Following skel files, which contain euler joints couldn't // pass EQUATIONS_OF_MOTION, are disabled. const auto uri = getList()[i]; - if (uri.toString() == "file://sample/skel/test/double_pendulum_euler_joint.skel" - || uri.toString() == "file://sample/skel/test/chainwhipa.skel" - || uri.toString() == "file://sample/skel/test/serial_chain_eulerxyz_joint.skel" - || uri.toString() == "file://sample/skel/test/simple_tree_structure_euler_joint.skel" - || uri.toString() == "file://sample/skel/test/tree_structure_euler_joint.skel" - || uri.toString() == "file://sample/skel/fullbody1.skel") + if (uri.toString() == "dart://sample/skel/test/double_pendulum_euler_joint.skel" + || uri.toString() == "dart://sample/skel/test/chainwhipa.skel" + || uri.toString() == "dart://sample/skel/test/serial_chain_eulerxyz_joint.skel" + || uri.toString() == "dart://sample/skel/test/simple_tree_structure_euler_joint.skel" + || uri.toString() == "dart://sample/skel/test/tree_structure_euler_joint.skel" + || uri.toString() == "dart://sample/skel/fullbody1.skel") { continue; } @@ -2033,7 +2033,7 @@ TEST_F(DynamicsTest, HybridDynamics) // Load world and skeleton WorldPtr world = utils::SkelParser::readWorld( - "file://sample/skel/test/hybrid_dynamics_test.skel"); + "dart://sample/skel/test/hybrid_dynamics_test.skel"); world->setTimeStep(timeStep); EXPECT_TRUE(world != nullptr); EXPECT_NEAR(world->getTimeStep(), timeStep, tol); diff --git a/unittests/comprehensive/test_ForwardKinematics.cpp b/unittests/comprehensive/test_ForwardKinematics.cpp index 5294f3947121..0de6cd2d9688 100644 --- a/unittests/comprehensive/test_ForwardKinematics.cpp +++ b/unittests/comprehensive/test_ForwardKinematics.cpp @@ -178,7 +178,7 @@ TEST(FORWARD_KINEMATICS, JACOBIAN_PARTIAL_CHANGE) dart::utils::DartLoader loader; SkeletonPtr skeleton1 = - loader.parseSkeleton("file://sample/urdf/KR5/KR5 sixx R650.urdf"); + loader.parseSkeleton("dart://sample/urdf/KR5/KR5 sixx R650.urdf"); SkeletonPtr skeleton2 = skeleton1->clone(); @@ -219,7 +219,7 @@ TEST(FORWARD_KINEMATICS, JACOBIAN_END_EFFECTOR_CHANGE) dart::utils::DartLoader loader; SkeletonPtr skeleton1 = - loader.parseSkeleton("file://sample/urdf/KR5/KR5 sixx R650.urdf"); + loader.parseSkeleton("dart://sample/urdf/KR5/KR5 sixx R650.urdf"); BodyNode* last_bn1 = skeleton1->getBodyNode(skeleton1->getNumBodyNodes()-1); EndEffector* ee1 = last_bn1->createEndEffector(); diff --git a/unittests/comprehensive/test_Joints.cpp b/unittests/comprehensive/test_Joints.cpp index 0afb48885cd1..776046376ef9 100644 --- a/unittests/comprehensive/test_Joints.cpp +++ b/unittests/comprehensive/test_Joints.cpp @@ -386,7 +386,7 @@ TEST_F(JOINTS, COMMAND_LIMIT) { simulation::WorldPtr myWorld = utils::SkelParser::readWorld( - "file://sample/skel/test/joint_limit_test.skel"); + "dart://sample/skel/test/joint_limit_test.skel"); EXPECT_TRUE(myWorld != nullptr); dynamics::SkeletonPtr pendulum = myWorld->getSkeleton("double_pendulum"); @@ -428,7 +428,7 @@ TEST_F(JOINTS, POSITION_LIMIT) simulation::WorldPtr myWorld = utils::SkelParser::readWorld( - "file://sample/skel/test/joint_limit_test.skel"); + "dart://sample/skel/test/joint_limit_test.skel"); EXPECT_TRUE(myWorld != nullptr); myWorld->setGravity(Eigen::Vector3d(0.0, 0.0, 0.0)); @@ -503,7 +503,7 @@ void testJointCoulombFrictionForce(double _timeStep) simulation::WorldPtr myWorld = utils::SkelParser::readWorld( - "file://sample/skel/test/joint_friction_test.skel"); + "dart://sample/skel/test/joint_friction_test.skel"); EXPECT_TRUE(myWorld != nullptr); myWorld->setGravity(Eigen::Vector3d(0.0, 0.0, 0.0)); @@ -816,7 +816,7 @@ TEST_F(JOINTS, JOINT_COULOMB_FRICTION_AND_POSITION_LIMIT) simulation::WorldPtr myWorld = utils::SkelParser::readWorld( - "file://sample/skel/test/joint_friction_test.skel"); + "dart://sample/skel/test/joint_friction_test.skel"); EXPECT_TRUE(myWorld != nullptr); myWorld->setGravity(Eigen::Vector3d(0.0, 0.0, 0.0)); diff --git a/unittests/comprehensive/test_Skeleton.cpp b/unittests/comprehensive/test_Skeleton.cpp index bd62004b5e19..cf3a865861ba 100644 --- a/unittests/comprehensive/test_Skeleton.cpp +++ b/unittests/comprehensive/test_Skeleton.cpp @@ -49,25 +49,25 @@ using namespace simulation; std::vector getFileList() { std::vector fileList; - fileList.push_back("file://sample/skel/test/chainwhipa.skel"); - fileList.push_back("file://sample/skel/test/single_pendulum.skel"); - fileList.push_back("file://sample/skel/test/single_pendulum_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/single_pendulum_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/double_pendulum.skel"); - fileList.push_back("file://sample/skel/test/double_pendulum_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/double_pendulum_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_revolute_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_eulerxyz_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_20.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_40.skel"); - fileList.push_back("file://sample/skel/test/simple_tree_structure.skel"); - fileList.push_back("file://sample/skel/test/simple_tree_structure_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/simple_tree_structure_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/tree_structure.skel"); - fileList.push_back("file://sample/skel/test/tree_structure_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/tree_structure_ball_joint.skel"); - fileList.push_back("file://sample/skel/fullbody1.skel"); + fileList.push_back("dart://sample/skel/test/chainwhipa.skel"); + fileList.push_back("dart://sample/skel/test/single_pendulum.skel"); + fileList.push_back("dart://sample/skel/test/single_pendulum_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/single_pendulum_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/double_pendulum.skel"); + fileList.push_back("dart://sample/skel/test/double_pendulum_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/double_pendulum_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_revolute_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_eulerxyz_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_ball_joint_20.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_ball_joint_40.skel"); + fileList.push_back("dart://sample/skel/test/simple_tree_structure.skel"); + fileList.push_back("dart://sample/skel/test/simple_tree_structure_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/simple_tree_structure_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/tree_structure.skel"); + fileList.push_back("dart://sample/skel/test/tree_structure_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/tree_structure_ball_joint.skel"); + fileList.push_back("dart://sample/skel/fullbody1.skel"); return fileList; } diff --git a/unittests/comprehensive/test_SoftDynamics.cpp b/unittests/comprehensive/test_SoftDynamics.cpp index eb6dcea5f8a7..d5709ddbfc15 100644 --- a/unittests/comprehensive/test_SoftDynamics.cpp +++ b/unittests/comprehensive/test_SoftDynamics.cpp @@ -117,7 +117,7 @@ class SoftDynamicsTest : public ::testing::Test //============================================================================== void SoftDynamicsTest::SetUp() { - list.push_back("file://sample/skel/test/test_drop_box.skel"); + list.push_back("dart://sample/skel/test/test_drop_box.skel"); } //============================================================================== diff --git a/unittests/comprehensive/test_World.cpp b/unittests/comprehensive/test_World.cpp index 0957b6f6cd3e..0f38a6403279 100644 --- a/unittests/comprehensive/test_World.cpp +++ b/unittests/comprehensive/test_World.cpp @@ -163,25 +163,25 @@ TEST(World, Cloning) { // Create a list of skel files to test with std::vector fileList; - fileList.push_back("file://sample/skel/test/chainwhipa.skel"); - fileList.push_back("file://sample/skel/test/single_pendulum.skel"); - fileList.push_back("file://sample/skel/test/single_pendulum_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/single_pendulum_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/double_pendulum.skel"); - fileList.push_back("file://sample/skel/test/double_pendulum_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/double_pendulum_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_revolute_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_eulerxyz_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_20.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_40.skel"); - fileList.push_back("file://sample/skel/test/simple_tree_structure.skel"); - fileList.push_back("file://sample/skel/test/simple_tree_structure_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/simple_tree_structure_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/tree_structure.skel"); - fileList.push_back("file://sample/skel/test/tree_structure_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/tree_structure_ball_joint.skel"); - fileList.push_back("file://sample/skel/fullbody1.skel"); + fileList.push_back("dart://sample/skel/test/chainwhipa.skel"); + fileList.push_back("dart://sample/skel/test/single_pendulum.skel"); + fileList.push_back("dart://sample/skel/test/single_pendulum_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/single_pendulum_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/double_pendulum.skel"); + fileList.push_back("dart://sample/skel/test/double_pendulum_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/double_pendulum_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_revolute_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_eulerxyz_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_ball_joint_20.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_ball_joint_40.skel"); + fileList.push_back("dart://sample/skel/test/simple_tree_structure.skel"); + fileList.push_back("dart://sample/skel/test/simple_tree_structure_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/simple_tree_structure_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/tree_structure.skel"); + fileList.push_back("dart://sample/skel/test/tree_structure_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/tree_structure_ball_joint.skel"); + fileList.push_back("dart://sample/skel/fullbody1.skel"); std::vector worlds; for(std::size_t i=0; i fileList; - fileList.push_back("file://sample/skel/test/chainwhipa.skel"); - fileList.push_back("file://sample/skel/test/single_pendulum.skel"); - fileList.push_back("file://sample/skel/test/single_pendulum_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/single_pendulum_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/double_pendulum.skel"); - fileList.push_back("file://sample/skel/test/double_pendulum_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/double_pendulum_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_revolute_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_eulerxyz_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_20.skel"); - fileList.push_back("file://sample/skel/test/serial_chain_ball_joint_40.skel"); - fileList.push_back("file://sample/skel/test/simple_tree_structure.skel"); - fileList.push_back("file://sample/skel/test/simple_tree_structure_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/simple_tree_structure_ball_joint.skel"); - fileList.push_back("file://sample/skel/test/tree_structure.skel"); - fileList.push_back("file://sample/skel/test/tree_structure_euler_joint.skel"); - fileList.push_back("file://sample/skel/test/tree_structure_ball_joint.skel"); - fileList.push_back("file://sample/skel/fullbody1.skel"); + fileList.push_back("dart://sample/skel/test/chainwhipa.skel"); + fileList.push_back("dart://sample/skel/test/single_pendulum.skel"); + fileList.push_back("dart://sample/skel/test/single_pendulum_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/single_pendulum_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/double_pendulum.skel"); + fileList.push_back("dart://sample/skel/test/double_pendulum_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/double_pendulum_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_revolute_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_eulerxyz_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_ball_joint_20.skel"); + fileList.push_back("dart://sample/skel/test/serial_chain_ball_joint_40.skel"); + fileList.push_back("dart://sample/skel/test/simple_tree_structure.skel"); + fileList.push_back("dart://sample/skel/test/simple_tree_structure_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/simple_tree_structure_ball_joint.skel"); + fileList.push_back("dart://sample/skel/test/tree_structure.skel"); + fileList.push_back("dart://sample/skel/test/tree_structure_euler_joint.skel"); + fileList.push_back("dart://sample/skel/test/tree_structure_ball_joint.skel"); + fileList.push_back("dart://sample/skel/fullbody1.skel"); std::vector worlds; for(std::size_t i=0; i #include -#include "dart/utils/SampleResourceRetriever.hpp" +#include "dart/utils/DartResourceRetriever.hpp" using namespace dart; //============================================================================== -TEST(SampleResourceRetriever, ExistsAndRetrieve) +TEST(DartResourceRetriever, ExistsAndRetrieve) { - auto retriever = utils::SampleResourceRetriever::create(); + auto retriever = utils::DartResourceRetriever::create(); EXPECT_FALSE(retriever->exists("unknown://test")); EXPECT_FALSE(retriever->exists("unknown://sample/test")); - EXPECT_FALSE(retriever->exists("file://unknown/test")); - EXPECT_FALSE(retriever->exists("file://sample/does/not/exist")); - EXPECT_TRUE(retriever->exists("file://sample/skel/shapes.skel")); + EXPECT_FALSE(retriever->exists("dart://unknown/test")); + EXPECT_FALSE(retriever->exists("dart://sample/does/not/exist")); + EXPECT_TRUE(retriever->exists("dart://sample/skel/shapes.skel")); EXPECT_EQ(nullptr, retriever->retrieve("unknown://test")); EXPECT_EQ(nullptr, retriever->retrieve("unknown://sample/test")); - EXPECT_EQ(nullptr, retriever->retrieve("file://unknown/test")); - EXPECT_EQ(nullptr, retriever->retrieve("file://sample/does/not/exist")); - EXPECT_NE(nullptr, retriever->retrieve("file://sample/skel/shapes.skel")); + EXPECT_EQ(nullptr, retriever->retrieve("dart://unknown/test")); + EXPECT_EQ(nullptr, retriever->retrieve("dart://sample/does/not/exist")); + EXPECT_NE(nullptr, retriever->retrieve("dart://sample/skel/shapes.skel")); } //============================================================================== diff --git a/unittests/unit/test_FileInfoWorld.cpp b/unittests/unit/test_FileInfoWorld.cpp index 013a79d29a05..ec50e64d82ef 100644 --- a/unittests/unit/test_FileInfoWorld.cpp +++ b/unittests/unit/test_FileInfoWorld.cpp @@ -58,7 +58,7 @@ TEST(FileInfoWorld, Basic) FileInfoWorld worldFile; WorldPtr world = SkelParser::readWorld( - "file://sample/skel/test/file_info_world_test.skel"); + "dart://sample/skel/test/file_info_world_test.skel"); EXPECT_TRUE(world != nullptr); Recording* recording1 = nullptr; diff --git a/unittests/unit/test_PackageResourceRetriever.cpp b/unittests/unit/test_PackageResourceRetriever.cpp index 961b00f3413a..16d2c5cede35 100644 --- a/unittests/unit/test_PackageResourceRetriever.cpp +++ b/unittests/unit/test_PackageResourceRetriever.cpp @@ -53,14 +53,14 @@ TEST(PackageResourceRetriever, exists_DelegateFails_ReturnsFalse) { // GTest breaks the string concatenation. #ifdef _WIN32 - const char* expected = "file:///" "file://sample/test/foo"; + const char* expected = "file:///" "dart://sample/test/foo"; #else - const char* expected = "file://" "file://sample/test/foo"; + const char* expected = "file://" "dart://sample/test/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", "file://sample/test"); + retriever.addPackageDirectory("test", "dart://sample/test"); EXPECT_FALSE(retriever.exists(Uri::createFromString("package://test/foo"))); ASSERT_EQ(1u, mockRetriever->mExists.size()); @@ -72,7 +72,7 @@ TEST(PackageResourceRetriever, exists_UnsupportedUri_ReturnsFalse) { auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", "file://sample/test"); + retriever.addPackageDirectory("test", "dart://sample/test"); EXPECT_FALSE(retriever.exists(Uri::createFromString("foo://test/foo"))); EXPECT_TRUE(mockRetriever->mExists.empty()); @@ -82,14 +82,14 @@ TEST(PackageResourceRetriever, exists_UnsupportedUri_ReturnsFalse) TEST(PackageResourceRetriever, exists_StripsTrailingSlash) { #ifdef _WIN32 - const char* expected = "file:///" "file://sample/test/foo"; + const char* expected = "file:///" "dart://sample/test/foo"; #else - const char* expected = "file://" "file://sample/test/foo"; + const char* expected = "file://" "dart://sample/test/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", "file://sample/test/"); + retriever.addPackageDirectory("test", "dart://sample/test/"); EXPECT_TRUE(retriever.exists(Uri::createFromString("package://test/foo"))); ASSERT_EQ(1u, mockRetriever->mExists.size()); @@ -100,15 +100,15 @@ TEST(PackageResourceRetriever, exists_StripsTrailingSlash) TEST(PackageResourceRetriever, exists_FirstUriSucceeds) { #ifdef _WIN32 - const char* expected = "file:///" "file://sample/test1/foo"; + const char* expected = "file:///" "dart://sample/test1/foo"; #else - const char* expected = "file://" "file://sample/test1/foo"; + const char* expected = "file://" "dart://sample/test1/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", "file://sample/test1"); - retriever.addPackageDirectory("test", "file://sample/test2"); + retriever.addPackageDirectory("test", "dart://sample/test1"); + retriever.addPackageDirectory("test", "dart://sample/test2"); EXPECT_TRUE(retriever.exists(Uri::createFromString("package://test/foo"))); ASSERT_EQ(1u, mockRetriever->mExists.size()); @@ -119,17 +119,17 @@ TEST(PackageResourceRetriever, exists_FirstUriSucceeds) TEST(PackageResourceRetriever, exists_FallsBackOnSecondUri) { #ifdef _WIN32 - const char* expected1 = "file:///" "file://sample/test1/foo"; - const char* expected2 = "file:///" "file://sample/test2/foo"; + const char* expected1 = "file:///" "dart://sample/test1/foo"; + const char* expected2 = "file:///" "dart://sample/test2/foo"; #else - const char* expected1 = "file://" "file://sample/test1/foo"; - const char* expected2 = "file://" "file://sample/test2/foo"; + const char* expected1 = "file://" "dart://sample/test1/foo"; + const char* expected2 = "file://" "dart://sample/test2/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", "file://sample/test1"); - retriever.addPackageDirectory("test", "file://sample/test2"); + retriever.addPackageDirectory("test", "dart://sample/test1"); + retriever.addPackageDirectory("test", "dart://sample/test2"); EXPECT_FALSE(retriever.exists(Uri::createFromString("package://test/foo"))); ASSERT_EQ(2u, mockRetriever->mExists.size()); @@ -152,14 +152,14 @@ TEST(PackageResourceRetriever, retrieve_DelegateFails_ReturnsNull) { // GTest breaks the string concatenation. #ifdef _WIN32 - const char* expected = "file:///" "file://sample/test/foo"; + const char* expected = "file:///" "dart://sample/test/foo"; #else - const char* expected = "file://" "file://sample/test/foo"; + const char* expected = "file://" "dart://sample/test/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", "file://sample/test"); + retriever.addPackageDirectory("test", "dart://sample/test"); EXPECT_EQ(nullptr, retriever.retrieve(Uri::createFromString("package://test/foo"))); EXPECT_TRUE(mockRetriever->mExists.empty()); @@ -171,7 +171,7 @@ TEST(PackageResourceRetriever, retrieve_UnsupportedUri_ReturnsNull) { auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", "file://sample/test"); + retriever.addPackageDirectory("test", "dart://sample/test"); EXPECT_EQ(nullptr, retriever.retrieve(Uri::createFromString("foo://test/foo"))); EXPECT_TRUE(mockRetriever->mExists.empty()); @@ -181,14 +181,14 @@ TEST(PackageResourceRetriever, retrieve_UnsupportedUri_ReturnsNull) TEST(PackageResourceRetriever, retrieve_StripsTrailingSlash) { #ifdef _WIN32 - const char* expected = "file:///" "file://sample/test/foo"; + const char* expected = "file:///" "dart://sample/test/foo"; #else - const char* expected = "file://" "file://sample/test/foo"; + const char* expected = "file://" "dart://sample/test/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", "file://sample/test/"); + retriever.addPackageDirectory("test", "dart://sample/test/"); EXPECT_TRUE(retriever.retrieve(Uri::createFromString("package://test/foo")) != nullptr); EXPECT_TRUE(mockRetriever->mExists.empty()); @@ -199,15 +199,15 @@ TEST(PackageResourceRetriever, retrieve_StripsTrailingSlash) TEST(PackageResourceRetriever, retrieve_FirstUriSucceeds) { #ifdef _WIN32 - const char* expected = "file:///" "file://sample/test1/foo"; + const char* expected = "file:///" "dart://sample/test1/foo"; #else - const char* expected = "file://" "file://sample/test1/foo"; + const char* expected = "file://" "dart://sample/test1/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", "file://sample/test1"); - retriever.addPackageDirectory("test", "file://sample/test2"); + retriever.addPackageDirectory("test", "dart://sample/test1"); + retriever.addPackageDirectory("test", "dart://sample/test2"); EXPECT_TRUE(retriever.retrieve(Uri::createFromString("package://test/foo")) != nullptr); EXPECT_TRUE(mockRetriever->mExists.empty()); @@ -218,17 +218,17 @@ TEST(PackageResourceRetriever, retrieve_FirstUriSucceeds) TEST(PackageResourceRetriever, retrieve_FallsBackOnSecondUri) { #ifdef _WIN32 - const char* expected1 = "file:///" "file://sample/test1/foo"; - const char* expected2 = "file:///" "file://sample/test2/foo"; + const char* expected1 = "file:///" "dart://sample/test1/foo"; + const char* expected2 = "file:///" "dart://sample/test2/foo"; #else - const char* expected1 = "file://" "file://sample/test1/foo"; - const char* expected2 = "file://" "file://sample/test2/foo"; + const char* expected1 = "file://" "dart://sample/test1/foo"; + const char* expected2 = "file://" "dart://sample/test2/foo"; #endif auto mockRetriever = std::make_shared(); PackageResourceRetriever retriever(mockRetriever); - retriever.addPackageDirectory("test", "file://sample/test1"); - retriever.addPackageDirectory("test", "file://sample/test2"); + retriever.addPackageDirectory("test", "dart://sample/test1"); + retriever.addPackageDirectory("test", "dart://sample/test2"); EXPECT_EQ(nullptr, retriever.retrieve(Uri::createFromString("package://test/foo"))); EXPECT_TRUE(mockRetriever->mExists.empty()); diff --git a/unittests/unit/test_SdfParser.cpp b/unittests/unit/test_SdfParser.cpp index 66d678fe7eac..a45920fbbf49 100644 --- a/unittests/unit/test_SdfParser.cpp +++ b/unittests/unit/test_SdfParser.cpp @@ -52,7 +52,7 @@ TEST(SdfParser, SDFSingleBodyWithoutJoint) // Regression test for #444 WorldPtr world = SdfParser::readWorld( - "file://sample/sdf/test/single_bodynode_skeleton.world"); + "dart://sample/sdf/test/single_bodynode_skeleton.world"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel = world->getSkeleton(0); @@ -77,12 +77,12 @@ TEST(SdfParser, ParsingSDFFiles) // Create a list of sdf files to test with where the sdf files contains World std::vector worldFiles; - worldFiles.push_back("file://sample/sdf/benchmark.world"); - worldFiles.push_back("file://sample/sdf/double_pendulum.world"); - worldFiles.push_back("file://sample/sdf/double_pendulum_with_base.world"); - worldFiles.push_back("file://sample/sdf/empty.world"); - worldFiles.push_back("file://sample/sdf/ground.world"); - worldFiles.push_back("file://sample/sdf/test/single_bodynode_skeleton.world"); + worldFiles.push_back("dart://sample/sdf/benchmark.world"); + worldFiles.push_back("dart://sample/sdf/double_pendulum.world"); + worldFiles.push_back("dart://sample/sdf/double_pendulum_with_base.world"); + worldFiles.push_back("dart://sample/sdf/empty.world"); + worldFiles.push_back("dart://sample/sdf/ground.world"); + worldFiles.push_back("dart://sample/sdf/test/single_bodynode_skeleton.world"); std::vector worlds; for (const auto& worldFile : worldFiles) @@ -99,8 +99,8 @@ TEST(SdfParser, ParsingSDFFiles) // Create another list of sdf files to test with where the sdf files contains // Skeleton std::vector skeletonFiles; - skeletonFiles.push_back("file://sample/sdf/atlas/atlas_v3_no_head.sdf"); - skeletonFiles.push_back("file://sample/sdf/atlas/atlas_v3_no_head_soft_feet.sdf"); + skeletonFiles.push_back("dart://sample/sdf/atlas/atlas_v3_no_head.sdf"); + skeletonFiles.push_back("dart://sample/sdf/atlas/atlas_v3_no_head_soft_feet.sdf"); auto world = std::make_shared(); std::vector skeletons; @@ -122,7 +122,7 @@ TEST(SdfParser, ParsingSDFFiles) //============================================================================== TEST(SdfParser, ReadMaterial) { - std::string sdf_filename = "file://sample/sdf/quad.sdf"; + std::string sdf_filename = "dart://sample/sdf/quad.sdf"; SkeletonPtr skeleton = SdfParser::readSkeleton(sdf_filename); EXPECT_TRUE(nullptr != skeleton); auto bodynode = skeleton->getBodyNode(0); diff --git a/unittests/unit/test_SkelParser.cpp b/unittests/unit/test_SkelParser.cpp index 15625aaf9727..a5c8878bc29a 100644 --- a/unittests/unit/test_SkelParser.cpp +++ b/unittests/unit/test_SkelParser.cpp @@ -89,7 +89,7 @@ TEST(SkelParser, DataStructure) //============================================================================== TEST(SkelParser, EmptyWorld) { - WorldPtr world = SkelParser::readWorld("file://sample/skel/test/empty.skel"); + WorldPtr world = SkelParser::readWorld("dart://sample/skel/test/empty.skel"); EXPECT_TRUE(world != nullptr); EXPECT_EQ(world->getTimeStep(), 0.001); @@ -107,7 +107,7 @@ TEST(SkelParser, EmptyWorld) TEST(SkelParser, SinglePendulum) { WorldPtr world = SkelParser::readWorld( - "file://sample/skel/test/single_pendulum.skel"); + "dart://sample/skel/test/single_pendulum.skel"); EXPECT_TRUE(world != nullptr); EXPECT_EQ(world->getTimeStep(), 0.001); @@ -127,7 +127,7 @@ TEST(SkelParser, SinglePendulum) TEST(SkelParser, SerialChain) { WorldPtr world = SkelParser::readWorld( - "file://sample/skel/test/serial_chain_ball_joint.skel"); + "dart://sample/skel/test/serial_chain_ball_joint.skel"); EXPECT_TRUE(world != nullptr); EXPECT_EQ(world->getTimeStep(), 0.001); @@ -150,7 +150,7 @@ TEST(SkelParser, VariousShapes) // world can simulate it successfully. WorldPtr world = SkelParser::readWorld( - "file://sample/skel/test/test_shapes.skel"); + "dart://sample/skel/test/test_shapes.skel"); for (auto i = 0u; i < 100; ++i) world->step(); @@ -166,7 +166,7 @@ TEST(SkelParser, RigidAndSoftBodies) using namespace utils; WorldPtr world = SkelParser::readWorld( - "file://sample/skel/test/test_articulated_bodies.skel"); + "dart://sample/skel/test/test_articulated_bodies.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); @@ -191,7 +191,7 @@ TEST(SkelParser, PlanarJoint) using namespace utils; WorldPtr world = SkelParser::readWorld( - "file://sample/skel/test/planar_joint.skel"); + "dart://sample/skel/test/planar_joint.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton1"); @@ -301,7 +301,7 @@ TEST(SkelParser, PlanarJoint) TEST(SKEL_PARSER, JointActuatorType) { WorldPtr world = SkelParser::readWorld( - "file://sample/skel/test/joint_actuator_type_test.skel"); + "dart://sample/skel/test/joint_actuator_type_test.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); @@ -334,7 +334,7 @@ TEST(SKEL_PARSER, JointActuatorType) TEST(SkelParser, DofAttributes) { WorldPtr world = SkelParser::readWorld( - "file://sample/skel/test/dof_attribute_test.skel"); + "dart://sample/skel/test/dof_attribute_test.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); @@ -412,7 +412,7 @@ TEST(SkelParser, JointDynamicsElements) { WorldPtr world = SkelParser::readWorld( - "file://sample/skel/test/joint_dynamics_elements_test.skel"); + "dart://sample/skel/test/joint_dynamics_elements_test.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); @@ -444,7 +444,7 @@ TEST(SkelParser, JointDynamicsElements) TEST(SkelParser, Shapes) { WorldPtr world - = SkelParser::readWorld("file://sample//skel/test/test_shapes.skel"); + = SkelParser::readWorld("dart://sample//skel/test/test_shapes.skel"); EXPECT_NE(world, nullptr); const auto numSkels = world->getNumSkeletons(); diff --git a/unittests/unit/test_VskParser.cpp b/unittests/unit/test_VskParser.cpp index 0b12d06218bd..9f76b02bd1ad 100644 --- a/unittests/unit/test_VskParser.cpp +++ b/unittests/unit/test_VskParser.cpp @@ -54,7 +54,7 @@ TEST(VskParser, EmptySkeleton) EXPECT_TRUE(world != nullptr); SkeletonPtr skeleton - = VskParser::readSkeleton("file://sample/vsk/test/empty.vsk"); + = VskParser::readSkeleton("dart://sample/vsk/test/empty.vsk"); EXPECT_TRUE(skeleton == nullptr); world->addSkeleton(skeleton); @@ -70,17 +70,17 @@ TEST(VskParser, SingleStepSimulations) EXPECT_NE(world , nullptr); SkeletonPtr nick - = VskParser::readSkeleton("file://sample/vsk/Nick01.vsk"); + = VskParser::readSkeleton("dart://sample/vsk/Nick01.vsk"); EXPECT_NE(nick , nullptr); EXPECT_EQ(nick->getNumMarkers(), 53u); SkeletonPtr sehoon - = VskParser::readSkeleton("file://sample/vsk/SehoonVSK3.vsk"); + = VskParser::readSkeleton("dart://sample/vsk/SehoonVSK3.vsk"); EXPECT_NE(sehoon, nullptr); EXPECT_EQ(nick->getNumMarkers(), 53u); SkeletonPtr yuting - = VskParser::readSkeleton("file://sample/vsk/Yuting.vsk"); + = VskParser::readSkeleton("dart://sample/vsk/Yuting.vsk"); EXPECT_NE(yuting, nullptr); EXPECT_EQ(nick->getNumMarkers(), 53u);