Skip to content

Commit

Permalink
move to pybind and move simulator initialization to Python side
Browse files Browse the repository at this point in the history
  • Loading branch information
mikaelarguedas committed Dec 22, 2017
1 parent 7256b29 commit 1ef6b7c
Show file tree
Hide file tree
Showing 4 changed files with 47 additions and 22 deletions.
4 changes: 2 additions & 2 deletions backend/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,8 @@ delphyne_build_tests(${gtest_sources})
find_package(PythonLibs 2.7 REQUIRED)
include_directories(${PYTHON_INCLUDE_DIRS})

find_package(Boost COMPONENTS python REQUIRED)
include_directories(${Boost_INCLUDE_DIR})
find_package(pybind11 REQUIRED)
include_directories(${pybind11_INCLUDE_DIRS})

# Build the simulation support for python bindings as a library.
add_library(simulation-support
Expand Down
20 changes: 19 additions & 1 deletion backend/python_bindings_example.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,11 @@
import time

from launcher import Launcher

from pydrake.common import AddResourceSearchPath

from simulation_runner_py import AutomotiveSimulator
from simulation_runner_py import SimpleCarState
from simulation_runner_py import SimulatorRunner


Expand Down Expand Up @@ -102,6 +107,15 @@ def random_print():
print("One in five hundred")


def create_and_init_automotive_simulator():
simulator = AutomotiveSimulator()
state = SimpleCarState()
state.y = 0.0
simulator.AddPriusSimpleCar("0", "DRIVING_COMMAND_0", state)

return simulator


def main():
"""Spawn an automotive simulator making use of the python bindings"""
stats = SimulationStats()
Expand All @@ -111,6 +125,10 @@ def main():
lcm_ign_bridge = "duplex-ign-lcm-bridge"
ign_visualizer = "visualizer"

drake_install_path = get_from_env_or_fail('DRAKE_INSTALL_PATH')
AddResourceSearchPath(os.path.join(drake_install_path, "share", "drake"))

simulator = create_and_init_automotive_simulator()
try:
launcher.launch([lcm_ign_bridge, "1"])
teleop_config = os.path.join(delphyne_ws_dir,
Expand All @@ -120,7 +138,7 @@ def main():
"layoutWithTeleop.config")
launcher.launch([ign_visualizer, teleop_config])

runner = SimulatorRunner()
runner = SimulatorRunner(simulator, 0.001)
# Add a callback to record and print statistics
runner.AddStepCallback(stats.record_tick)
# Add a second callback that prints a message roughly every 500 calls
Expand Down
1 change: 0 additions & 1 deletion backend/simulation_runner.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@
#include <ignition/msgs.hh>
#include <ignition/transport/Node.hh>

#include <Python.h>
#include <pybind11/pybind11.h>

#include "backend/automotive_simulator.h"
Expand Down
44 changes: 26 additions & 18 deletions backend/simulation_runner_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,41 +35,49 @@
#include "backend/automotive_simulator.h"
#include "backend/simulation_runner.h"

namespace py = pybind11;

using delphyne::backend::AutomotiveSimulator;
using delphyne::backend::SimulatorRunner;
using drake::automotive::SimpleCarState;

// Since we are not yet exporting the AutomotiveSimulator class we need to
// provide a ready-to-run SimulatorRunner. To do so we create a parameterless
// constructor that sets up a simulation runner with a prius car in it. As we
// keep adding python bindings to C++ classes this code will be moved to the
// python scripts that launches the simulation.

namespace py = pybind11;

namespace {
PYBIND11_MODULE(simulation_runner_py, m) {
py::class_<SimulatorRunner>(m, "SimulatorRunner")
.def(py::init([](void) {
// TODO(mikaelaguedas) All this should be done in Python using pydrake
// and custom bindings for AutomotiveSimulator and SimpleCarState
drake::AddResourceSearchPath(std::string(std::getenv("DRAKE_INSTALL_PATH")) +
"/share/drake");

auto simulator =
std::make_unique<delphyne::backend::AutomotiveSimulator<double>>();

// Add a Prius car.
drake::automotive::SimpleCarState<double> state;
state.set_y(0.0);
simulator->AddPriusSimpleCar("0", "DRIVING_COMMAND_0", state);

// Instantiate the simulator runner and pass the simulator.
const double time_step = 0.001;
.def(py::init([](std::unique_ptr<AutomotiveSimulator<double>> simulator, double time_step) {
return std::make_unique<SimulatorRunner>(std::move(simulator), time_step);
}))
.def("Start", &SimulatorRunner::Start)
.def("Stop", &SimulatorRunner::Stop)
.def("AddStepCallback", &SimulatorRunner::AddStepCallback);
;
py::class_<AutomotiveSimulator<double>, std::unique_ptr<AutomotiveSimulator<double>>>(m, "AutomotiveSimulator")
.def(py::init([](void) {
return std::make_unique<AutomotiveSimulator<double>>();
}))
.def("Start", &AutomotiveSimulator<double>::Start)
.def("AddPriusSimpleCar", &AutomotiveSimulator<double>::AddPriusSimpleCar)
.def("AddMobilControlledSimpleCar", &AutomotiveSimulator<double>::AddMobilControlledSimpleCar)
// TODO(mikaelarguedas) bind more method depending on what we need
// .def("AddPriusTrajectoryCar", &AutomotiveSimulator<double>::AddPriusTrajectoryCar)
// .def("AddPriusMaliputRailcar", &AutomotiveSimulator<double>::AddPriusMaliputRailcar)
// .def("AddIdmControlledPriusMaliputRailcar", &AutomotiveSimulator<double>::AddIdmControlledPriusMaliputRailcar)
// .def("SetMaliputRailcarAccelerationCommand", &AutomotiveSimulator<double>::SetMaliputRailcarAccelerationCommand)
;
py::class_<SimpleCarState<double>>(m, "SimpleCarState")
.def(py::init<>())
.def_property("x", &SimpleCarState<double>::x, &SimpleCarState<double>::set_x)
.def_property("y", &SimpleCarState<double>::y, &SimpleCarState<double>::set_y)
.def_property("heading", &SimpleCarState<double>::heading, &SimpleCarState<double>::set_heading)
.def_property("velocity", &SimpleCarState<double>::velocity, &SimpleCarState<double>::set_velocity)
.def("get_coordinates_names", &SimpleCarState<double>::GetCoordinateNames)
;
}

} // namespace

0 comments on commit 1ef6b7c

Please sign in to comment.