Skip to content

Commit a25304b

Browse files
committed
Use upstream owen statespace
F
1 parent ade4c17 commit a25304b

File tree

5 files changed

+5
-6
lines changed

5 files changed

+5
-6
lines changed

README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ docker run --network=host -it -v $(pwd):/root/ros2_ws/src/ethz-asl/terrain-navig
6262
## Running an example of the planner
6363
In order to run the examples, build the `terrain_planner_benchmark` package.
6464
```
65-
colcon build --packages-up-to terrain_planner_benchmark
65+
colcon build --packages-up-to terrain_planner_benchmark --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo
6666
```
6767
Run a simple planning example:
6868
```

terrain_planner/CMakeLists.txt

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -44,8 +44,6 @@ pkg_check_modules(ODE REQUIRED ode)
4444
# Libraries
4545
add_library(${PROJECT_NAME}
4646
src/common.cpp
47-
src/DubinsAirplane.cpp
48-
src/DubinsPath.cpp
4947
src/terrain_ompl_rrt.cpp
5048
src/terrain_ompl.cpp
5149
src/visualization.cpp

terrain_planner/include/terrain_planner/ompl_setup.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,6 @@
1111
#include <ompl/geometric/planners/rrt/RRTstar.h>
1212

1313
#include "ompl/base/SpaceInformation.h"
14-
#include "terrain_planner/DubinsAirplane.hpp"
1514
#include "terrain_planner/terrain_ompl.h"
1615

1716
enum PlannerType { RRTSTAR, INFORMED_RRTSTAR, RRTCONNECT, BITSTAR, FMTSTAR };

terrain_planner/include/terrain_planner/terrain_ompl_rrt.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,8 @@
4747
#include "terrain_navigation/path.h"
4848
#include "terrain_planner/ompl_setup.h"
4949

50+
#include <ompl/base/spaces/OwenStateSpace.h>
51+
5052
class TerrainOmplRrt {
5153
public:
5254
TerrainOmplRrt();
@@ -71,7 +73,7 @@ class TerrainOmplRrt {
7173
void setupProblem(const Eigen::Vector3d& start_pos, const Eigen::Vector3d& goal) {
7274
this->setupProblem(
7375
start_pos, goal,
74-
problem_setup_->getStateSpace()->as<fw_planning::spaces::DubinsAirplaneStateSpace>()->getMinTurningRadius());
76+
problem_setup_->getStateSpace()->as<ompl::spaces::OwenStateSpace>()->getMinTurningRadius());
7577
};
7678

7779
/**

terrain_planner_benchmark/README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ See [74](https://github.com/ethz-asl/terrain-navigation/issues/74) for details.
77

88
Build this repository, and your terrain source.
99
```
10-
colcon build --packages-up-to terrain_planner_benchmark terrain_models
10+
colcon build --packages-up-to terrain_planner_benchmark terrain_models --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo
1111
```
1212

1313
## Terrain Planner Benchmark Node

0 commit comments

Comments
 (0)