-
Notifications
You must be signed in to change notification settings - Fork 1.3k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Add bindings for a small subset of maliput api and dragway backend
- Loading branch information
1 parent
7c29b62
commit 995bec1
Showing
5 changed files
with
242 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,96 @@ | ||
# -*- python -*- | ||
|
||
load("@drake//tools/install:install.bzl", "install") | ||
load("//tools/lint:lint.bzl", "add_lint_tests") | ||
load( | ||
"//tools/skylark:pybind.bzl", | ||
"drake_pybind_library", | ||
"get_drake_py_installs", | ||
"get_pybind_package_info", | ||
) | ||
load( | ||
"//tools/skylark:drake_py.bzl", | ||
"drake_py_binary", | ||
"drake_py_library", | ||
"drake_py_test", | ||
) | ||
|
||
package(default_visibility = [ | ||
"//bindings/pydrake:__subpackages__", | ||
]) | ||
|
||
# This determines how `PYTHONPATH` is configured, and how to install the | ||
# bindings. | ||
PACKAGE_INFO = get_pybind_package_info("//bindings") | ||
|
||
# @note Symbols are NOT imported directly into | ||
# `__init__.py` to simplify dependency management, meaning that | ||
# classes are organized by their directory structure rather than | ||
# by C++ namespace. | ||
drake_py_library( | ||
name = "module_py", | ||
srcs = ["__init__.py"], | ||
imports = PACKAGE_INFO.py_imports, | ||
deps = [ | ||
"//bindings/pydrake:common_py", | ||
], | ||
) | ||
|
||
drake_pybind_library( | ||
name = "api_py", | ||
cc_deps = [ | ||
"//automotive/maliput/api", | ||
], | ||
cc_so_name = "api", | ||
cc_srcs = ["api_py.cc"], | ||
package_info = PACKAGE_INFO, | ||
py_deps = [ | ||
":module_py", | ||
], | ||
) | ||
|
||
drake_pybind_library( | ||
name = "dragway_py", | ||
cc_deps = [ | ||
"//automotive/maliput/dragway", | ||
], | ||
cc_so_name = "dragway", | ||
cc_srcs = ["dragway_py.cc"], | ||
package_info = PACKAGE_INFO, | ||
py_deps = [ | ||
":module_py", | ||
], | ||
) | ||
|
||
PY_LIBRARIES_WITH_INSTALL = [ | ||
":maliput_py", | ||
] | ||
|
||
PY_LIBRARIES = [ | ||
":module_py", | ||
] | ||
|
||
drake_py_library( | ||
name = "maliput", | ||
imports = PACKAGE_INFO.py_imports, | ||
deps = PY_LIBRARIES_WITH_INSTALL + PY_LIBRARIES, | ||
) | ||
|
||
install( | ||
name = "install", | ||
targets = PY_LIBRARIES, | ||
py_dest = PACKAGE_INFO.py_dest, | ||
deps = get_drake_py_installs(PY_LIBRARIES_WITH_INSTALL), | ||
) | ||
|
||
drake_py_test( | ||
name = "maliput_test", | ||
size = "small", | ||
deps = [ | ||
":api_py", | ||
":dragway_py", | ||
"//bindings/pydrake/systems", | ||
], | ||
) | ||
|
||
add_lint_tests() |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1 @@ | ||
# Blank Python module. |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,30 @@ | ||
#include <pybind11/eigen.h> | ||
#include <pybind11/pybind11.h> | ||
|
||
#include "drake/automotive/maliput/api/lane_data.h" | ||
#include "drake/automotive/maliput/api/road_geometry.h" | ||
#include "drake/bindings/pydrake/pydrake_pybind.h" | ||
|
||
namespace drake { | ||
namespace pydrake { | ||
|
||
PYBIND11_MODULE(api, m) { | ||
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace. | ||
using namespace drake::maliput::api; | ||
|
||
m.doc() = "Bindings for the Maliput API."; | ||
|
||
py::class_<RoadGeometryId>(m, "RoadGeometryId") | ||
.def(py::init<std::string>()); | ||
|
||
py::class_<GeoPosition> (m, "GeoPosition") | ||
.def(py::init<double, double, double>()) | ||
.def("xyz", &GeoPosition::xyz); | ||
|
||
py::class_<LanePosition>(m, "LanePosition") | ||
.def(py::init<double, double, double>()) | ||
.def("srh", &LanePosition::srh); | ||
} | ||
|
||
} // namespace pydrake | ||
} // namespace drake |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,42 @@ | ||
#include <pybind11/eigen.h> | ||
#include <pybind11/pybind11.h> | ||
|
||
#include "drake/automotive/maliput/dragway/lane.h" | ||
#include "drake/automotive/maliput/dragway/junction.h" | ||
#include "drake/automotive/maliput/dragway/road_geometry.h" | ||
#include "drake/automotive/maliput/dragway/segment.h" | ||
#include "drake/bindings/pydrake/pydrake_pybind.h" | ||
|
||
namespace drake { | ||
namespace pydrake { | ||
|
||
PYBIND11_MODULE(dragway, m) { | ||
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace. | ||
using namespace drake::maliput; | ||
|
||
m.doc() = "Bindings for the Dragway backend."; | ||
|
||
py::class_<dragway::RoadGeometry>(m, "RoadGeometry") | ||
.def(py::init<api::RoadGeometryId, int, double, double, double, double, | ||
double, double>()) | ||
.def("junction", &dragway::RoadGeometry::junction, py_reference_internal, | ||
// Keep alive, reference: `return` keeps `self` alive. | ||
py::keep_alive<0, 1>()); | ||
|
||
py::class_<dragway::Junction>(m, "Junction") | ||
.def("segment", &dragway::Junction::segment, py_reference_internal, | ||
// Keep alive, reference: `return` keeps `self` alive. | ||
py::keep_alive<0, 1>()); | ||
|
||
py::class_<dragway::Segment>(m, "Segment") | ||
.def("lane", &dragway::Segment::lane, py_reference_internal, | ||
// Keep alive, reference: `return` keeps `self` alive. | ||
py::keep_alive<0, 1>()); | ||
|
||
py::class_<dragway::Lane>(m, "Lane") | ||
.def("ToLanePosition", &dragway::Lane::ToLanePosition) | ||
.def("ToGeoPosition", &dragway::Lane::ToGeoPosition); | ||
} | ||
|
||
} // namespace pydrake | ||
} // namespace drake |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,73 @@ | ||
#!/usr/bin/env python | ||
|
||
from __future__ import print_function | ||
|
||
import copy | ||
import unittest | ||
import numpy as np | ||
|
||
import pydrake.systems.framework as framework | ||
from pydrake.maliput.api import ( | ||
RoadGeometryId, | ||
LanePosition, | ||
GeoPosition, | ||
) | ||
import pydrake.maliput.dragway as dragway | ||
|
||
|
||
# Tests the bindings for the API and backend implementations. | ||
class TestMaliput(unittest.TestCase): | ||
def test_api(self): | ||
srh = [4., 5., 6.] | ||
lane_pos = LanePosition(srh[0], srh[1], srh[2]) | ||
self.assertTrue(len(lane_pos.srh()) == 3) | ||
for i in [0, 1, 2]: | ||
self.assertTrue(lane_pos.srh()[i] == srh[i]) | ||
xyz = [1., 2., 3.] | ||
geo_pos = GeoPosition(xyz[0], xyz[1], xyz[2]) | ||
self.assertTrue(len(geo_pos.xyz()) == 3) | ||
for i in [0, 1, 2]: | ||
self.assertTrue(geo_pos.xyz()[i] == xyz[i]) | ||
|
||
def test_dragway(self): | ||
kNumLanes = 2 | ||
kLength = 100. | ||
kLaneWidth = 4. | ||
kShoulderWidth = 1. | ||
kHeight = 5. | ||
kTol = 1e-6 | ||
|
||
# Instantiate a two-lane straight road. | ||
rg_id = RoadGeometryId("two_lane_road") | ||
rg = dragway.RoadGeometry( | ||
rg_id, kNumLanes, kLength, kLaneWidth, kShoulderWidth, kHeight, | ||
kTol, kTol) | ||
segment = rg.junction(0).segment(0) | ||
lane_0 = segment.lane(0) | ||
lane_1 = segment.lane(1) | ||
|
||
# Test the . | ||
lane_pos = LanePosition(0., 0., 0.) | ||
geo_pos_result = lane_0.ToGeoPosition(lane_pos) | ||
geo_pos_expected = GeoPosition(0., -kLaneWidth / 2., 0.) | ||
for i in [0, 1, 2]: | ||
self.assertTrue(geo_pos_result.xyz()[i] == | ||
geo_pos_expected.xyz()[i]) | ||
|
||
geo_pos = GeoPosition(1., kLaneWidth / 2., 3.) | ||
nearest_pos = GeoPosition(0., 0., 0.) | ||
distance = 0. | ||
lane_pos_result = \ | ||
lane_1.ToLanePosition(geo_pos, nearest_pos, distance) | ||
lane_pos_expected = LanePosition(1., 0., 3.) | ||
for i in [0, 1, 2]: | ||
self.assertTrue(lane_pos_result.srh()[i] == | ||
lane_pos_expected.srh()[i]) | ||
self.assertTrue(nearest_pos.xyz()[i] == geo_pos.xyz()[i]) | ||
self.assertTrue(distance == 0.) | ||
|
||
# TODO(jadecastro) Add more maliput backends as needed. | ||
|
||
|
||
if __name__ == '__main__': | ||
unittest.main() |