Skip to content

Commit

Permalink
[python] Add worldEntity util (#1308)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina authored Jan 25, 2022
1 parent 5619121 commit 3eb5691
Show file tree
Hide file tree
Showing 10 changed files with 124 additions and 19 deletions.
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.
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -20,13 +20,13 @@
#
# Now you can run the example:
#
# python3 examples/python/helperFixture.py
# python3 examples/scripts/python_api/helperFixture.py

import os
import time

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

Expand All @@ -39,24 +39,36 @@
post_iterations = 0
iterations = 0
pre_iterations = 0


def on_post_udpate_cb(_info, _ecm):
global post_iterations
post_iterations += 1
# print(_info.sim_time)
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)
Expand Down
2 changes: 0 additions & 2 deletions include/ignition/gazebo/EventManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -140,8 +140,6 @@ namespace ignition
}
};

/// This was originally a unique_ptr, but pybind11 was failing because it
/// was not able to copy the class
/// \brief Container of used signals.
private: std::unordered_map<TypeInfoRef,
std::unique_ptr<ignition::common::Event>,
Expand Down
1 change: 1 addition & 0 deletions python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ pybind11_add_module(gazebo SHARED
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
)

Expand Down
41 changes: 41 additions & 0 deletions python/src/ignition/gazebo/Util.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
/*
* 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 <pybind11/pybind11.h>
#include <pybind11/stl.h>

#include <iostream>

#include <ignition/gazebo/Util.hh>
#include "Util.hh"

namespace ignition
{
namespace gazebo
{
namespace python
{
void defineGazeboUtil(pybind11::module &_module)
{
_module.def("world_entity",
pybind11::overload_cast<const EntityComponentManager &>(
&ignition::gazebo::worldEntity),
"Get the first world entity that's found.");
}
} // namespace python
} // namespace gazebo
} // namespace ignition
37 changes: 37 additions & 0 deletions python/src/ignition/gazebo/Util.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
/*
* 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.
*/

#ifndef IGNITION_GAZEBO_PYTHON__UTIL_HH_
#define IGNITION_GAZEBO_PYTHON__UTIL_HH_

#include <pybind11/pybind11.h>

#include <ignition/gazebo/Util.hh>

namespace ignition
{
namespace gazebo
{
namespace python
{
/// Define a pybind11 wrapper for a ignition::gazebo::Util
/// \param[in] _module a pybind11 module to add the definition to
void defineGazeboUtil(pybind11::module &_module);
} // namespace python
} // namespace gazebo
} // namespace ignition

#endif // IGNITION_GAZEBO_PYTHON__WORLD_HH_
2 changes: 2 additions & 0 deletions python/src/ignition/gazebo/_ignition_gazebo_pybind11.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include "ServerConfig.hh"
#include "TestFixture.hh"
#include "UpdateInfo.hh"
#include "Util.hh"
#include "World.hh"

PYBIND11_MODULE(gazebo, m) {
Expand All @@ -34,4 +35,5 @@ PYBIND11_MODULE(gazebo, m) {
ignition::gazebo::python::defineGazeboTestFixture(m);
ignition::gazebo::python::defineGazeboUpdateInfo(m);
ignition::gazebo::python::defineGazeboWorld(m);
ignition::gazebo::python::defineGazeboUtil(m);
}
7 changes: 6 additions & 1 deletion python/test/testFixture_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
import unittest

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

Expand All @@ -40,6 +40,11 @@ def on_post_udpate_cb(_info, _ecm):
def on_pre_udpate_cb(_info, _ecm):
global pre_iterations
pre_iterations += 1
world_e = world_entity(_ecm);
self.assertEqual(1, world_e)
w = World(world_e)
v = w.gravity(_ecm)
self.assertEqual(Vector3d(0, 0, -9.8), v)

def on_udpate_cb(_info, _ecm):
global iterations
Expand Down
19 changes: 11 additions & 8 deletions tutorials/python_interfaces.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ step simulation and check entities and components.
helper = HelperFixture(os.path.join(file_path, 'gravity.sdf'))
```

- **Step 2**: Write your `configure`, `pretupdate`, `update` or `postupdate` code:
- **Step 2**: Write your `pretupdate`, `update` or `postupdate` code:
```python
def on_post_udpate_cb(_info, _ecm):
# <your code here>
Expand All @@ -41,18 +41,21 @@ step simulation and check entities and components.

# Run the example

In the [examples/python](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo6/examples/python) folder there is a Python script
shows make use of this API. If you compiled Ignition Gazebo from source you should modify your `PYTHONPATH`:
In the
[examples/scripts/python_api](https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo6/examples/scripts/python_api)
folder there is a Python script that shows how to make use of this API.

```bash
export PYTHONPATH=$PYTHONPATH:<path to ws>/install/lib/python
```
> If you compiled Ignition Gazebo from source you should modify your `PYTHONPATH`:
>
> ```bash
> export PYTHONPATH=$PYTHONPATH:<path to ws>/install/lib/python
> ```

Now you can run the example:

```bash
$ python3 examples/python/helperFixture.py
[Msg] Loading SDF world file[/home/ahcorde/ignition_fortress/src/ign-gazebo/examples/python/gravity.sdf].
$ python3 examples/scripts/python_api/helperFixture.py
[Msg] Loading SDF world file[/home/ahcorde/ignition_fortress/src/ign-gazebo/examples/scripts/python_api/gravity.sdf].
[Dbg] [Physics.cc:789] Loaded [ignition::physics::dartsim::Plugin] from library [/home/ahcorde/ignition_fortress/install/lib/ign-physics-5/engine-plugins/libignition-physics-dartsim-plugin.so]
[Dbg] [SimulationRunner.cc:909] Loaded system [ignition::gazebo::systems::Physics] for entity [1]
[Msg] Loaded level [3]
Expand Down

0 comments on commit 3eb5691

Please sign in to comment.