Skip to content

Commit

Permalink
Merge branch 'ign-gazebo6' into aditya/odom_offset
Browse files Browse the repository at this point in the history
  • Loading branch information
adityapande-1995 committed Mar 8, 2022
2 parents d314d42 + f5bb284 commit 1c565de
Show file tree
Hide file tree
Showing 80 changed files with 3,717 additions and 313 deletions.
1 change: 1 addition & 0 deletions .github/ci/packages-focal.apt
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
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
34 changes: 33 additions & 1 deletion CMakeLists.txt
Expand Up @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)
#============================================================================
# Initialize the project
#============================================================================
project(ignition-gazebo6 VERSION 6.5.0)
project(ignition-gazebo6 VERSION 6.7.0)

#============================================================================
# Find ignition-cmake
Expand All @@ -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
61 changes: 59 additions & 2 deletions Changelog.md
@@ -1,8 +1,65 @@
## Ignition Gazebo 6.x

### Ignition Gazebo 6.X.X (202X-XX-XX)
### Ignition Gazebo 6.7.0 (2022-02-24)

1. Added Python interfaces to some Ignition Gazebo methods
* [Pull request #1219](https://github.com/ignitionrobotics/ign-gazebo/pull/1219)

1. Use pose multiplication instead of addition
* [Pull request #1369](https://github.com/ignitionrobotics/ign-gazebo/pull/1369)

1. Disables Failing Buoyancy Tests on Win32
* [Pull request #1368](https://github.com/ignitionrobotics/ign-gazebo/pull/1368)

1. Extend ShaderParam system to support loading different shader languages
* [Pull request #1335](https://github.com/ignitionrobotics/ign-gazebo/pull/1335)

1. Populate names of colliding entities in contact points message
* [Pull request #1351](https://github.com/ignitionrobotics/ign-gazebo/pull/1351)

1. Refactor System functionality into SystemManager
* [Pull request #1340](https://github.com/ignitionrobotics/ign-gazebo/pull/1340)

1. GzSceneManager: Prevent crash boom when inserted from menu
* [Pull request #1371](https://github.com/ignitionrobotics/ign-gazebo/pull/1371)

### Ignition Gazebo 6.6.0 (2022-02-24)

1. Fix accessing empty JointPosition component in lift drag plugin
* [Pull request #1366](https://github.com/ignitionrobotics/ign-gazebo/pull/1366)

1. Add parameter to TrajectoryFollower stop rotation when bearing is reached
* [Pull request #1349](https://github.com/ignitionrobotics/ign-gazebo/pull/1349)

1. Support disabling pose publisher from publishing top level model pose
* [Pull request #1342](https://github.com/ignitionrobotics/ign-gazebo/pull/1342)

1. Added more sensor properties to scene/info topic
* [Pull request #1344](https://github.com/ignitionrobotics/ign-gazebo/pull/1344)

1. Adding ability to pause/resume the trajectory follower behavior.
* [Pull request #1347](https://github.com/ignitionrobotics/ign-gazebo/pull/1347)

1. Logs a warning if a mode is not clearly sepecified.
* [Pull request #1307](https://github.com/ignitionrobotics/ign-gazebo/pull/1307)

1. JointStatePublisher publish parent, child and axis data
* [Pull request #1345](https://github.com/ignitionrobotics/ign-gazebo/pull/1345)

1. Fixed light gui component inspector
* [Pull request #1337](https://github.com/ignitionrobotics/ign-gazebo/pull/1337)

1. Fix UNIT_SdfGenerator_TEST
* [Pull request #1319](https://github.com/ignitionrobotics/ign-gazebo/pull/1319)

1. Add elevator system
* [Pull request #535](https://github.com/ignitionrobotics/ign-gazebo/pull/535)

1. Removed unused variables in shapes plugin
* [Pull request #1321](https://github.com/ignitionrobotics/ign-gazebo/pull/1321)

### Ignition Gazebo 6.5.0 (2022-02-15)

### Ignition Gazebo 6.5.0 (202X-XX-XX)
1. New trajectory follower system
* [Pull request #1332](https://github.com/ignitionrobotics/ign-gazebo/pull/1332)

Expand Down
6 changes: 6 additions & 0 deletions examples/scripts/python_api/README.md
@@ -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
@@ -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
@@ -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)

0 comments on commit 1c565de

Please sign in to comment.