Enable Python bindings for Dubins path segments #1261
Conversation
|
First off, thanks for creating these python bindings. I thought about it and decided it was too much effort. I can't reproduce your results. The code compiles, but when I run DubinsAirplane.py I get this error: I built your branch inside a Docker container using this Dockerfile. Can you add more details on your setup (versions of OS, compiler, boost, castxml, pyplusplus, pygccxml, ...)? You can attach your CMakeCache.txt, which should have all the relevant info. |
|
Nvm, I see now that you only added the bindings for OwenStateSpace and not the others: Let me try again by adding similar lines for the other PathTypes. |
|
Yes, only added the optional wrapper for
castxml --version
castxml version 0.6.10
CastXML project maintained and supported by Kitware (kitware.com).
Homebrew clang version 19.1.6
Target: x86_64-apple-darwin24.2.0
Thread model: posix
I tried applying similar changes to the |
|
This might be helpful for creating bindings for raw pointers or std::array<T,N>: https://pyplusplus.readthedocs.io/en/latest/functions/call_policies/as_tuple.html |
|
The branch I linked above (https://github.com/srmainwaring/ompl/tree/prs/pr-fix-path-segment-array-binding) uses that code adapted to It may be an ordering issue, but even when I moved the wrapper, in this case self.add_c_array_3_wrapper('ompl::base::DubinsStateSpace::DubinsPathSegmentType')to the top of the Note: I may have messed the naming of the registration method up in this branch while squashing and rebasing. |
|
I checked out your std::array version and can't figure out why it doesn't work. It seems like it should. I did some benchmarking with this PR. Although the use of std::vectors for fixed-size arrays is not ideal, it doesn't seem to negatively impact performance, so I think we can let that slide. |
| path_type = space.getPath(from_state, to_state) | ||
| db_path = path_type.path_ | ||
|
|
||
| print(f"from_state: {from_state[0]:.1f}, {from_state[1]:.1f}, " |
There was a problem hiding this comment.
This is a nice demonstration that the Python bindings work, but it is only correct for OwenStateSpace. It doesn't work for the other types. I'd leave the whole if path.getStateCount() > 1: ... block out
|
|
||
|
|
||
| # add wrappers for std::optional types | ||
| self.add_optional_wrapper('ompl::base::OwenStateSpace::PathType') |
There was a problem hiding this comment.
| self.add_optional_wrapper('ompl::base::OwenStateSpace::PathType') | |
| self.add_optional_wrapper('ompl::base::OwenStateSpace::PathType') | |
| self.add_optional_wrapper('ompl::base::VanaStateSpace::PathType') | |
| self.add_optional_wrapper('ompl::base::VanaOwenStateSpace::PathType') |
It has me confused as well. The registration does not seem materially different from that for Thanks for the feedback. I'll update the PR with the changes. Do you prefer separate commits to follow the feedback, or rebased and squashed (I'm used to ArduPilot which prefers the latter, but either is good by me). For some context: I'm using the existing OMPL bindings in a Python port of the ETHZ terrain_navigation library. The port is here: terrain_nav_py, and the intention is to initially have it integrated into a MAVProxy module for mission generation (ArduPilot/MAVProxy#1533). It's all working fairly well, but using the OwenStateSpace rather than the Python implemented DubinsAirplaneStateSpace will give a significant performance uptick, hence the desire for the additional bindings. If you'd prefer to hold off a merge until I can resolve getting the bindings for |
- Add a binding generator for std::optional<T>. - Apply to OwenStateSpace::getPath. - Apply to remaining state space types requiring them. Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
- Replace c-style arrays with std::vector, which has a binding generator. Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
3562725 to
19523f6
Compare
|
Let's merge this PR and consider a possible refactor to use std::array in a later PR. This PR works and doesn't negatively affect performance of non-Python code, so it's just a stylistic issue. We're about to release OMPL 1.7, so it'd be nice to have this in the release. |
|
@mamoll thanks! Is there a window prior to the 1.7 for a quick addition that exposes the PR here: #1264 |
Provide a binding generator for
std::optional<T>and change the storage type of the static array ofDubinsPathSegmentTypefrom c-style arrays tostd::vector. This is to allow the Python binding generator to generate interfaces for theDubinsPathreturned by thegetPathfunction in theDubinsStateSpace.This change is more intrusive than I would have liked (ideally the C++ code would not need to change to provide bindings). The preferred solution would be to add a generator for c-style arrays of fixed size, however attempts at this were not successful (see below).
Alternatives
Looked into providing bindings for the c-array types directly and also using
std::array<T, N>. For some reason neither of these approaches was successful. The bindings appear to have been generated by the compiler but the following errors are reported at runtime when loading the module (i.e.>>> from ompl import base as ob):TypeError: No to_python (by-value) converter found for C++ type: ompl::base::DubinsStateSpace::DubinsPathSegmentType [3]or in the case of
std::array:This branch (https://github.com/srmainwaring/ompl/tree/prs/pr-fix-path-segment-array-binding) contains a version of the
DubinsStateSpaceusingstd::array.Testing
The
DubinsAirplane.pydemo is updated to display details of the Dubins curve segments from the generated path.Debug: RRTstar: Planner range detected to be 7.242362 Warning: RRTstar requires a state space with symmetric distance and symmetric interpolation. at line 101 in /Users/rhys/Code/ompl/ompl/src/ompl/geometric/planners/rrt/src/RRTstar.cpp ... Info: RRTstar: Started planning with 1 states. Seeking a solution better than 0.00000. Info: RRTstar: Initial k-nearest value of 83 Info: RRTstar: Found an initial solution with a cost of 18.60 in 115 iterations (23 vertices in the graph) Info: RRTstar: Created 669 new states. Checked 224115 rewire options. 1 goal states in tree. Final solution cost 15.544 Info: Solution found in 10.113416 seconds -3.25318 6.34438 -2.35268 -0.225403 -3.22259 6.33686 -2.36956 -0.256906 -3.19225 6.32838 -2.38643 -0.288409 -3.16219 6.31894 -2.40331 -0.319912 -3.13245 6.30857 -2.42018 -0.351416 -3.10305 6.29726 -2.43706 -0.382919 -3.07402 6.28503 -2.45393 -0.414422 ... Path length is 15.543926579752133 from_state: -3.3, 6.3, -2.4, -0.2 to_state: -3.2, 6.3, -2.4, -0.3 path_type.phi: 0.00 path_type.deltaZ: -0.0169 path_type.numTurns: 0 path_type.path: DubinsPath[ type=RSL, length=0.0315032+0+0=0.0315032, reverse=0 ] path_type.path.type: DUBINS_RIGHT, DUBINS_STRAIGHT. DUBINS_LEFT path_type.path.length: 0.0315, 0.0000, 0.0000 path_type.path.reverse: False from_state: -3.2, 6.3, -2.4, -0.3 to_state: -3.2, 6.3, -2.4, -0.3 path_type.phi: 0.00 path_type.deltaZ: -0.0169 path_type.numTurns: 0 path_type.path: DubinsPath[ type=LSR, length=0+0+0.0315032=0.0315032, reverse=0 ] path_type.path.type: DUBINS_LEFT, DUBINS_STRAIGHT. DUBINS_RIGHT path_type.path.length: 0.0000, 0.0000, 0.0315 path_type.path.reverse: False ...