Skip to content

Commit

Permalink
Added Python interfaces to some Ignition Gazebo methods (#1219)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <[email protected]>
Co-authored-by: Louise Poubel <[email protected]>
Co-authored-by: Jose Luis Rivero <[email protected]>
  • Loading branch information
3 people authored Feb 25, 2022
1 parent 3b94bd2 commit ac989f8
Show file tree
Hide file tree
Showing 35 changed files with 1,674 additions and 0 deletions.
1 change: 1 addition & 0 deletions .github/ci/packages-focal.apt
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,4 @@ libdart-dev
libdart-external-ikfast-dev
libdart-external-odelcpsolver-dev
libdart-utils-urdf-dev
python3-ignition-math6
2 changes: 2 additions & 0 deletions .github/ci/packages.apt
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@ libsdformat12-dev
libtinyxml2-dev
libxi-dev
libxmu-dev
python3-distutils
python3-pybind11
qml-module-qt-labs-folderlistmodel
qml-module-qt-labs-settings
qml-module-qtqml-models2
Expand Down
32 changes: 32 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ find_package(ignition-cmake2 2.8.0 REQUIRED)
# Configure the project
#============================================================================
ign_configure_project(VERSION_SUFFIX)
set (CMAKE_CXX_STANDARD 17)

#============================================================================
# Set project-specific options
Expand All @@ -37,6 +38,14 @@ endif()
include(test/find_dri.cmake)
FindDRI()

option(USE_SYSTEM_PATHS_FOR_PYTHON_INSTALLATION
"Install python modules in standard system paths in the system"
OFF)

option(USE_DIST_PACKAGES_FOR_PYTHON
"Use dist-packages instead of site-package to install python modules"
OFF)

#============================================================================
# Search for project-specific dependencies
#============================================================================
Expand Down Expand Up @@ -167,6 +176,26 @@ ign_find_package(IgnProtobuf
PRETTY Protobuf)
set(Protobuf_IMPORT_DIRS ${ignition-msgs8_INCLUDE_DIRS})

#--------------------------------------
# Find python
include(IgnPython)
find_package(PythonLibs QUIET)
if (NOT PYTHONLIBS_FOUND)
IGN_BUILD_WARNING("Python is missing: Python interfaces are disabled.")
message (STATUS "Searching for Python - not found.")
else()
message (STATUS "Searching for Python - found version ${PYTHONLIBS_VERSION_STRING}.")

set(PYBIND11_PYTHON_VERSION 3)
find_package(pybind11 2.2 QUIET)

if (${pybind11_FOUND})
message (STATUS "Searching for pybind11 - found version ${pybind11_VERSION}.")
else()
IGN_BUILD_WARNING("pybind11 is missing: Python interfaces are disabled.")
message (STATUS "Searching for pybind11 - not found.")
endif()
endif()
# Plugin install dirs
set(IGNITION_GAZEBO_PLUGIN_INSTALL_DIR
${CMAKE_INSTALL_PREFIX}/${IGN_LIB_INSTALL_DIR}/ign-${IGN_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins
Expand All @@ -187,6 +216,9 @@ add_subdirectory(examples)
#============================================================================
ign_create_packages()

if (${pybind11_FOUND})
add_subdirectory(python)
endif()
#============================================================================
# Configure documentation
#============================================================================
Expand Down
6 changes: 6 additions & 0 deletions examples/scripts/python_api/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# Gazebo Python API

This example shows how to use Gazebo's Python API.

For more information, see the
[Python interfaces](https://ignitionrobotics.org/api/gazebo/6.4/python_interfaces.html) tutorial.
22 changes: 22 additions & 0 deletions examples/scripts/python_api/gravity.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="gravity">
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>

<model name="falling">
<link name="link">
<inertial>
<inertia>
<ixx>0.4</ixx>
<iyy>0.4</iyy>
<izz>0.4</izz>
</inertia>
<mass>1.0</mass>
</inertial>
</link>
</model>
</world>
</sdf>
85 changes: 85 additions & 0 deletions examples/scripts/python_api/testFixture.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,85 @@
#!/usr/bin/python3
# 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.

# If you compiled Ignition Gazebo from source you should modify your
# `PYTHONPATH`:
#
# export PYTHONPATH=$PYTHONPATH:<path to ws>/install/lib/python
#
# Now you can run the example:
#
# python3 examples/scripts/python_api/helperFixture.py

import os
import time

from ignition.common import set_verbosity
from ignition.gazebo import TestFixture, World, world_entity
from ignition.math import Vector3d
from sdformat import Element

set_verbosity(4)

file_path = os.path.dirname(os.path.realpath(__file__))

helper = TestFixture(os.path.join(file_path, 'gravity.sdf'))

post_iterations = 0
iterations = 0
pre_iterations = 0
first_iteration = True


def on_pre_udpate_cb(_info, _ecm):
global pre_iterations
global first_iteration
pre_iterations += 1
if first_iteration:
first_iteration = False
world_e = world_entity(_ecm);
print('World entity is ', world_e)
w = World(world_e)
v = w.gravity(_ecm)
print('Gravity ', v)
modelEntity = w.model_by_name(_ecm, 'falling')
print('Entity for falling model is: ', modelEntity)


def on_udpate_cb(_info, _ecm):
global iterations
iterations += 1


def on_post_udpate_cb(_info, _ecm):
global post_iterations
post_iterations += 1
if _info.sim_time.seconds == 1:
print('Post update sim time: ', _info.sim_time)


helper.on_post_update(on_post_udpate_cb)
helper.on_update(on_udpate_cb)
helper.on_pre_update(on_pre_udpate_cb)
helper.finalize()

server = helper.server()
server.run(False, 1000, False)

while(server.is_running()):
time.sleep(0.1)

print('iterations ', iterations)
print('post_iterations ', post_iterations)
print('pre_iterations ', pre_iterations)
99 changes: 99 additions & 0 deletions python/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
if(WIN32 AND CMAKE_BUILD_TYPE STREQUAL "Debug")
# pybind11 logic for setting up a debug build when both a debug and release
# python interpreter are present in the system seems to be pretty much broken.
# This works around the issue.
set(PYTHON_LIBRARIES "${PYTHON_DEBUG_LIBRARIES}")
endif()


if(USE_SYSTEM_PATHS_FOR_PYTHON_INSTALLATION)
if(${CMAKE_VERSION} VERSION_LESS "3.12.0")
execute_process(
COMMAND "${PYTHON_EXECUTABLE}" -c "if True:
from distutils import sysconfig as sc
print(sc.get_python_lib(plat_specific=True))"
OUTPUT_VARIABLE Python3_SITEARCH
OUTPUT_STRIP_TRAILING_WHITESPACE)
else()
# Get install variable from Python3 module
# Python3_SITEARCH is available from 3.12 on, workaround if needed:
find_package(Python3 COMPONENTS Interpreter)
endif()

if(USE_DIST_PACKAGES_FOR_PYTHON)
string(REPLACE "site-packages" "dist-packages" IGN_PYTHON_INSTALL_PATH ${Python3_SITEARCH})
endif()
else()
# If not a system installation, respect local paths
set(IGN_PYTHON_INSTALL_PATH ${IGN_LIB_INSTALL_DIR}/python)
endif()

# Set the build location and install location for a CPython extension
function(configure_build_install_location _library_name)
# Install library for actual use
install(TARGETS ${_library_name}
DESTINATION "${IGN_PYTHON_INSTALL_PATH}/ignition"
)
endfunction()

pybind11_add_module(gazebo SHARED
src/ignition/gazebo/_ignition_gazebo_pybind11.cc
src/ignition/gazebo/EntityComponentManager.cc
src/ignition/gazebo/EventManager.cc
src/ignition/gazebo/TestFixture.cc
src/ignition/gazebo/Server.cc
src/ignition/gazebo/ServerConfig.cc
src/ignition/gazebo/UpdateInfo.cc
src/ignition/gazebo/Util.cc
src/ignition/gazebo/World.cc
)

target_link_libraries(gazebo PRIVATE
${PROJECT_LIBRARY_TARGET_NAME}
sdformat${SDF_VER}::sdformat${SDF_VER}
ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER}
)

# TODO(ahcorde): Move this module to ign-common
pybind11_add_module(common SHARED
src/ignition/common/_ignition_common_pybind11.cc
src/ignition/common/Console.cc
)

target_link_libraries(common PRIVATE
ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER}
)

# TODO(ahcorde): Move this module to sdformat
pybind11_add_module(sdformat SHARED
src/ignition/sdformat/_sdformat_pybind11.cc
src/ignition/sdformat/Element.cc
)

target_link_libraries(sdformat PRIVATE
sdformat${SDF_VER}::sdformat${SDF_VER}
)

install(TARGETS sdformat
DESTINATION "${IGN_PYTHON_INSTALL_PATH}"
)

configure_build_install_location(gazebo)
configure_build_install_location(common)

if (BUILD_TESTING)
set(python_tests
testFixture_TEST
)

foreach (test ${python_tests})
add_test(NAME ${test}.py COMMAND
"${PYTHON_EXECUTABLE}" "${CMAKE_SOURCE_DIR}/python/test/${test}.py")

set(_env_vars)
list(APPEND _env_vars "PYTHONPATH=${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_LIBDIR}/python/")
list(APPEND _env_vars "LD_LIBRARY_PATH=${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_LIBDIR}:$ENV{LD_LIBRARY_PATH}")
set_tests_properties(${test}.py PROPERTIES
ENVIRONMENT "${_env_vars}")
endforeach()
endif()
31 changes: 31 additions & 0 deletions python/src/ignition/common/Console.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
// Copyright 2021 Open Source Robotics Foundation, Inc.
//
// 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/common/Console.hh>

#include "Console.hh"

namespace ignition
{
namespace common
{
namespace python
{
void SetVerbosity(int _verbosity)
{
ignition::common::Console::SetVerbosity(_verbosity);
}
}
}
}
31 changes: 31 additions & 0 deletions python/src/ignition/common/Console.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
// Copyright 2021 Open Source Robotics Foundation, Inc.
//
// 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.

#ifndef IGNITION_GAZEBO_PYTHON__CONSOLE_HH_
#define IGNITION_GAZEBO_PYTHON__CONSOLE_HH_

#include <pybind11/pybind11.h>

namespace ignition
{
namespace common
{
namespace python
{
void SetVerbosity(int _verbosity);
}
}
}

#endif
25 changes: 25 additions & 0 deletions python/src/ignition/common/_ignition_common_pybind11.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
// Copyright 2021 Open Source Robotics Foundation, Inc.
//
// 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 <pybind11/pybind11.h>

#include "Console.hh"

PYBIND11_MODULE(common, m) {
m.doc() = "Ignition Common Python Library.";

m.def(
"set_verbosity", &ignition::common::python::SetVerbosity,
"Set verbosity level.");
}
Loading

0 comments on commit ac989f8

Please sign in to comment.