Skip to content

Commit

Permalink
2 ➡️ 3 (#262)
Browse files Browse the repository at this point in the history
* [Citadel] Update tutorials (#204)

Signed-off-by: claireyywang <[email protected]>
Signed-off-by: anindex <[email protected]>

Co-authored-by: anindex <[email protected]>
Co-authored-by: Louise Poubel <[email protected]>
Co-authored-by: Claire Wang <[email protected]>
Co-authored-by: Steve Peters <[email protected]>

* Remove tools/code_check and update codecov (#257)

Signed-off-by: Louise Poubel <[email protected]>

* Fix dart deprecation warning (#263)

Copied from #262.

Signed-off-by: Steve Peters <[email protected]>

Co-authored-by: Claire Wang <[email protected]>
Co-authored-by: anindex <[email protected]>
Co-authored-by: Steve Peters <[email protected]>
  • Loading branch information
4 people authored Jun 18, 2021
2 parents 0ec547b + 8cc844f commit 01a3f49
Show file tree
Hide file tree
Showing 32 changed files with 602 additions and 6,855 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ jobs:
id: ci
uses: ignition-tooling/action-ignition-ci@bionic
with:
codecov-token: ${{ secrets.CODECOV_TOKEN }}
codecov-enabled: true
focal-ci:
runs-on: ubuntu-latest
name: Ubuntu Focal CI
Expand Down
4 changes: 3 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ project(ignition-physics3 VERSION 3.2.0)
#============================================================================
# Find ignition-cmake
#============================================================================
find_package(ignition-cmake2 2.1.0 REQUIRED)
find_package(ignition-cmake2 2.8.0 REQUIRED)

#============================================================================
# Configure the project
Expand Down Expand Up @@ -116,3 +116,5 @@ ign_create_docs(
"${IGNITION-PLUGIN_DOXYGEN_TAGFILE} = ${IGNITION-PLUGIN_API_URL}"
"${IGNITION-MATH_DOXYGEN_TAGFILE} = ${IGNITION-MATH_API_URL}"
)

file(COPY ${CMAKE_SOURCE_DIR}/tutorials/img/ DESTINATION ${CMAKE_BINARY_DIR}/doxygen/html/img/)
6 changes: 6 additions & 0 deletions examples/hello_world_loader/hello_world_loader.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
*
*/

////////////////////////////////////////////////////////////////////
//! [include statements]
#include <iostream>

#include <ignition/plugin/Loader.hh>
Expand All @@ -28,7 +30,10 @@
using Features = ignition::physics::FeatureList<
ignition::physics::GetEngineInfo
>;
//! [include statements]

////////////////////////////////////////////////////////////////////
//! [main]
int main(int argc, char **argv)
{
// User should provide path to plugin library
Expand Down Expand Up @@ -62,3 +67,4 @@ int main(int argc, char **argv)
std::cout << " engine name: " << engine->GetName() << std::endl;
}
}
//! [main]
12 changes: 12 additions & 0 deletions examples/hello_world_plugin/HelloWorldPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,18 +15,26 @@
*
*/

////////////////////////////////////////////////////////////
//! [include statements]
#include <ignition/physics/FeatureList.hh>
#include <ignition/physics/FeaturePolicy.hh>
#include <ignition/physics/GetEntities.hh>
#include <ignition/physics/Register.hh>
//! [include statements]

namespace mock
{
////////////////////////////////////////////////////////
//! [feature list]
// List of all features that this plugin will implement
struct HelloWorldFeatureList : ignition::physics::FeatureList<
ignition::physics::GetEngineInfo
> { };
//! [feature list]

////////////////////////////////////////////////////////
//! [implementation]
// The plugin class, which implements a 3D policy
class HelloWorldPlugin
: public ignition::physics::Implements3d<HelloWorldFeatureList>
Expand All @@ -52,10 +60,14 @@ namespace mock

std::string engineName;
};
//! [implementation]

////////////////////////////////////////////////////////
//! [register]
// Register plugin
IGN_PHYSICS_ADD_PLUGIN(
HelloWorldPlugin,
ignition::physics::FeaturePolicy3d,
HelloWorldFeatureList)
//! [register]
}
20 changes: 20 additions & 0 deletions examples/simple_plugin/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
cmake_minimum_required(VERSION 3.5 FATAL_ERROR)

set(IGN_PLUGIN_VER 1)
find_package(ignition-plugin${IGN_PLUGIN_VER} 1.1 REQUIRED COMPONENTS all)

set(IGN_PHYSICS_VER 2)
find_package(ignition-physics${IGN_PHYSICS_VER} REQUIRED)

add_library(SimplePlugin SHARED plugin.cc EntityManagementFeatures.cc)
target_link_libraries(SimplePlugin
PRIVATE
ignition-physics${IGN_PHYSICS_VER}::ignition-physics${IGN_PHYSICS_VER})

add_executable(PluginTest EntityManagementFeatures_TEST.cc)
target_link_libraries(PluginTest
ignition-plugin${IGN_PLUGIN_VER}::loader
ignition-physics${IGN_PHYSICS_VER}::ignition-physics${IGN_PHYSICS_VER})

target_compile_definitions(PluginTest PRIVATE
"simple_plugin_LIB=\"$<TARGET_FILE:SimplePlugin>\"")
31 changes: 31 additions & 0 deletions examples/simple_plugin/EntityManagementFeatures.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include <string>
#include "EntityManagementFeatures.hh"

using namespace ignition;
using namespace physics;
using namespace simpleplugin;

/////////////////////////////////////////////////
Identity EntityManagementFeatures::ConstructEmptyWorld(
const Identity &, const std::string &_name)
{
// Generate dummy identity
return this->GenerateIdentity(0);
}
50 changes: 50 additions & 0 deletions examples/simple_plugin/EntityManagementFeatures.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

//! [basic include]
#include <string>
#include <ignition/physics/Implements.hh>
//! [basic include]

//! [include feature]
#include <ignition/physics/ConstructEmpty.hh>

namespace ignition {
namespace physics {
namespace simpleplugin {

struct EntityManagementFeatureList : FeatureList<
ConstructEmptyWorldFeature
> { };

//! [include feature]

//! [override feature]
class EntityManagementFeatures :
public virtual Implements3d<EntityManagementFeatureList>
{
/// \brief Construct an empty dummy world.
/// \param[in] _engineID Identity for the engine.
/// \param[in] _name Name of the world.
public: Identity ConstructEmptyWorld(
const Identity &_engineID, const std::string &_name) override;
};

}
}
}
//! [override feature]
60 changes: 60 additions & 0 deletions examples/simple_plugin/EntityManagementFeatures_TEST.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include <iostream>

#include <ignition/plugin/Loader.hh>
#include <ignition/physics/RequestEngine.hh>
#include "EntityManagementFeatures.hh"

// Simple executable that loads the simple plugin and constructs a world.

struct TestFeatureList : ignition::physics::FeatureList<
ignition::physics::simpleplugin::EntityManagementFeatureList
> { };

int main(int argc, char *argv[])
{
// Load the custom plugin
ignition::plugin::Loader loader;
loader.LoadLib(simple_plugin_LIB);

auto simplePlugin =
loader.Instantiate("ignition::physics::simpleplugin::Plugin");

// Get the engine pointer
auto engine =
ignition::physics::RequestEngine3d<TestFeatureList>::From(simplePlugin);

if (nullptr == engine)
{
std::cerr << "Something went wrong, the engine is null" << std::endl;
return -1;
}

auto world = engine->ConstructEmptyWorld("empty world");

if (nullptr == world)
{
std::cerr << "Failed to create empty world" << std::endl;
return -1;
}

std::cout << "Created empty world!" << std::endl;

return 0;
}
47 changes: 47 additions & 0 deletions examples/simple_plugin/plugin.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include <ignition/physics/FeatureList.hh>
#include <ignition/physics/FeaturePolicy.hh>
#include <ignition/physics/Register.hh>

#include "EntityManagementFeatures.hh"

namespace ignition {
namespace physics {
namespace simpleplugin {

struct SimplePluginFeatures : FeatureList<
EntityManagementFeatureList
> { };

class Plugin :
public virtual EntityManagementFeatures,
public virtual Implements3d<SimplePluginFeatures>
{
using Identity = ignition::physics::Identity;
public: Identity InitiateEngine(std::size_t /*_engineID*/) override
{
return this->GenerateIdentity(0);
}
};

IGN_PHYSICS_ADD_PLUGIN(Plugin, FeaturePolicy3d, SimplePluginFeatures)

}
}
}
2 changes: 2 additions & 0 deletions include/ignition/physics/ConstructEmpty.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ namespace ignition {
namespace physics {

/////////////////////////////////////////////////
//! [ConstructEmptyWorld]
/// \brief This feature constructs an empty world and return its pointer
/// from the current physics engine in use.
class ConstructEmptyWorldFeature : public virtual Feature
Expand All @@ -48,6 +49,7 @@ class ConstructEmptyWorldFeature : public virtual Feature
const Identity &_engineID, const std::string &_name) = 0;
};
};
//! [ConstructEmptyWorld]

/////////////////////////////////////////////////
/// \brief This feature constructs an empty model and return its pointer
Expand Down
5 changes: 5 additions & 0 deletions test/plugins/DARTDoublePendulum.cc
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,12 @@ namespace mock

for (std::size_t i=0; i < robot->getNumJoints(); ++i)
{
// From upstream 6.10.0 or OSRF 6.10.0~osrf19~2021-06-10
#if DART_VERSION_AT_LEAST(6, 10, 0)
this->robot->getJoint(i)->setLimitEnforcement(false);
#else
this->robot->getJoint(i)->setPositionLimitEnforced(false);
#endif
this->robot->getJoint(i)->setDampingCoefficient(0, 0);
}

Expand Down
Loading

0 comments on commit 01a3f49

Please sign in to comment.