-
Notifications
You must be signed in to change notification settings - Fork 0
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Add bindings for AutomotiveSimulator #177
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -35,41 +35,70 @@ | |
#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); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Just a heads up (sorry for adding this post-merge): You should be able to use There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Thanks @EricCousineau-TRI , done in f3232e0 |
||
})) | ||
.def("Start", &SimulatorRunner::Start) | ||
.def("Stop", &SimulatorRunner::Stop) | ||
.def("AddStepCallback", &SimulatorRunner::AddStepCallback); | ||
; | ||
py::class_<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 | ||
// Needs drake::automotive::Curve2<double>& | ||
// .def("AddPriusTrajectoryCar", &AutomotiveSimulator<double>::AddPriusTrajectoryCar) | ||
// Needs: | ||
// - drake::automotive::LaneDirection | ||
// - drake::automotive::MaliputRailcarParams<T> | ||
// - drake::automotive::MaliputRailcarState<T> | ||
// .def("AddPriusMaliputRailcar", &AutomotiveSimulator<double>::AddPriusMaliputRailcar) | ||
// Needs: | ||
// - drake::automotive::LaneDirection | ||
// - drake::automotive::MaliputRailcarParams<T> | ||
// - drake::automotive::MaliputRailcarState<T> | ||
// .def("AddIdmControlledPriusMaliputRailcar", &AutomotiveSimulator<double>::AddIdmControlledPriusMaliputRailcar) | ||
// .def("SetMaliputRailcarAccelerationCommand", &AutomotiveSimulator<double>::SetMaliputRailcarAccelerationCommand) | ||
// Needs drake::maliput::api::RoadGeometry binding | ||
// .def("SetRoadGeometry", &AutomotiveSimulator<double>::SetRoadGeometry) | ||
// Needs drake::maliput::api::Lane binding | ||
// .def("FindLane", &AutomotiveSimulator<double>::FindLane) | ||
// Needs drake::systems::System<T> binding | ||
// .def("GetDiagramSystemByName", &AutomotiveSimulator<double>::GetDiagramSystemByName) | ||
// .def("Build", &AutomotiveSimulator<double>::Build) | ||
// .def("GetDiagram", &AutomotiveSimulator<double>::GetDiagram) | ||
// .def("StepBy", &AutomotiveSimulator<double>::StepBy) | ||
// Needs drake::systems::rendering::PoseBundle<T> binding | ||
// .def("GetCurrentPoses", &AutomotiveSimulator<double>::GetCurrentPoses) | ||
; | ||
// TODO(mikaelarguedas) Submit this to upstream Drake | ||
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 |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
BTW Below, the stripping could be done by
value.rstrip(' :')
.