Skip to content

Commit 0ee3bf8

Browse files
committed
Remove fw_planning statespace
Use upstream owen statespace F Use upstream owen statespace F F F
1 parent afee406 commit 0ee3bf8

File tree

19 files changed

+328
-3022
lines changed

19 files changed

+328
-3022
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_navigation_ros/include/terrain_navigation_ros/terrain_planner.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -242,7 +242,7 @@ class TerrainPlanner : public rclcpp::Node {
242242

243243
std::shared_ptr<TerrainMap> terrain_map_;
244244

245-
std::shared_ptr<fw_planning::spaces::DubinsAirplaneStateSpace> dubins_state_space_;
245+
std::shared_ptr<ompl::base::OwenStateSpace> dubins_state_space_;
246246
// std::shared_ptr<ViewUtilityMap> viewutility_map_;
247247
std::shared_ptr<TerrainOmplRrt> global_planner_;
248248
std::shared_ptr<Profiler> planner_profiler_;

terrain_navigation_ros/src/terrain_planner.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -163,7 +163,7 @@ TerrainPlanner::TerrainPlanner() : Node("terrain_planner") {
163163
terrain_map_ = std::make_shared<TerrainMap>();
164164

165165
// Initialize Dubins state space
166-
dubins_state_space_ = std::make_shared<fw_planning::spaces::DubinsAirplaneStateSpace>(goal_radius_);
166+
dubins_state_space_ = std::make_shared<ompl::base::OwenStateSpace>(goal_radius_);
167167
global_planner_ = std::make_shared<TerrainOmplRrt>(ompl::base::StateSpacePtr(dubins_state_space_));
168168
global_planner_->setMap(terrain_map_);
169169
global_planner_->setAltitudeLimits(max_elevation_, min_elevation_);

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

0 commit comments

Comments
 (0)