Skip to content
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

Initial draft of changes for online map / planner updates #12

Draft
wants to merge 24 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from 1 commit
Commits
Show all changes
24 commits
Select commit Hold shift + click to select a range
745d2d0
Add functionality to update map (and the planner state space boundari…
meychr Apr 5, 2021
51f0bac
Make class member of StateValidator private
meychr May 13, 2021
c8ad75d
Make some class functions constant
meychr May 13, 2021
0d0bcc0
Unify name of state space boundaries to StateSpaceBoundaries
meychr May 13, 2021
07efb89
Reorder member variables
meychr May 13, 2021
b492b7f
Implement getStartingState and getGoalState for OmplReedsSheppPlanner
meychr May 14, 2021
85723b8
Move ROS publishers and services to base class PlannerRos, use Planne…
meychr May 14, 2021
f24ce13
Make isStateValid constant
meychr May 14, 2021
11075fe
Fix typo
meychr May 14, 2021
8c0bc04
Move StateValidator functions to Planner interface
meychr May 14, 2021
0072859
Adapt se2_grid_map_generator config and add TODOs to fix frames
meychr May 19, 2021
db4a618
Set state space bounds changes
meychr May 19, 2021
2735940
Fix formatting
meychr May 19, 2021
6b3863b
Move getStateSpaceBoundaries to OmplPlanner
meychr May 19, 2021
4704095
Remove comment
meychr May 19, 2021
808bd65
Reorder code and remove TODO
meychr May 29, 2021
21e3385
Fix format
meychr Jun 7, 2021
5c1afb2
Implement map interface and occupancy map & adapt height map
meychr Jun 7, 2021
fc57077
Add ROS class for occupancy map
meychr Jun 7, 2021
632a7f6
Integrate new map for state space boundaries update, adapt tests
meychr Jun 7, 2021
db5da4d
Uncomment isTraversable again
meychr Jun 7, 2021
80db121
Make GridMapLazyStateValidatorRos similar to OccupancyMapRos
meychr Jun 7, 2021
ad3095d
Change config file to use elevation for collision checking in state v…
meychr Jun 7, 2021
d07c579
Increase footprint size in car_demo
meychr Jun 7, 2021
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
Uncomment isTraversable again
  • Loading branch information
meychr committed Jun 7, 2021
commit db5da4d149f10c160801f32f26815cd9bc0025c8
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@

namespace se2_planning {

enum StateValidityCheckingMethod : int { COLLISION = 0, TRAVERSABILITY = 1, ROBUST_TRAVERSABILITY = 2 };
enum StateValidityCheckingMethod : int { COLLISION = 0, TRAVERSABILITY = 1, TRAVERSABILITY_ITERATOR = 2, ROBUST_TRAVERSABILITY = 3 };

class GridMapLazyStateValidator : public GridMapStateValidator {
using BASE = GridMapStateValidator;
Expand Down Expand Up @@ -64,8 +64,8 @@ class GridMapLazyStateValidator : public GridMapStateValidator {
void computeFootprintPoints(const grid_map::GridMap& gridMap, const RobotFootprint& footprint, std::vector<Vertex>* footprintPoints);
bool isInCollision(const SE2state& state, const std::vector<Vertex>& footprint, const grid_map::GridMap& gridMap,
const std::string& obstacleLayer, const double collisionThreshold);
// bool isTraversable(const SE2state& state, const std::vector<Vertex>& footprint, const grid_map::GridMap& gridMap,
// const std::string& traversabilityLayer, const double traversabilityThreshold);
bool isTraversable(const SE2state& state, const std::vector<Vertex>& footprint, const grid_map::GridMap& gridMap,
const std::string& traversabilityLayer, const double traversabilityThreshold);
bool isTraversableIterator(const SE2state& state, const RobotFootprint& footprint, const grid_map::GridMap& gridMap,
const std::string& traversabilityLayer, const double traversabilityThreshold);
bool isTraversableRobustIterator(const SE2state& state, const RobotFootprint& footprint, const grid_map::GridMap& gridMap,
Expand Down
90 changes: 48 additions & 42 deletions se2_planning/src/GridMapLazyStateValidator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,7 @@ void GridMapLazyStateValidator::initialize() {
if (isUseEarlyStoppingHeuristic_) {
addExtraPointsForEarlyStopping(nominalFootprint_, &nominalFootprintPoints_, seed_);
}

isInitializeCalled_ = true;
}

Expand All @@ -97,6 +98,8 @@ bool GridMapLazyStateValidator::isStateValid(const State& state) const {
case StateValidityCheckingMethod::COLLISION:
return !isInCollision(se2state, nominalFootprintPoints_, gridMap_, obstacleLayerName_, minStateValidityThreshold_);
case StateValidityCheckingMethod::TRAVERSABILITY:
return isTraversable(se2state, nominalFootprintPoints_, gridMap_, obstacleLayerName_, minStateValidityThreshold_);
case StateValidityCheckingMethod::TRAVERSABILITY_ITERATOR:
return isTraversableIterator(se2state, nominalFootprint_, gridMap_, obstacleLayerName_, minStateValidityThreshold_);
case StateValidityCheckingMethod::ROBUST_TRAVERSABILITY:
return isTraversableRobustIterator(se2state, nominalFootprint_, gridMap_, obstacleLayerName_, minStateValidityThreshold_,
Expand Down Expand Up @@ -143,12 +146,10 @@ bool isInCollision(const SE2state& state, const std::vector<Vertex>& footprint,
try {
const auto v = transformOperator(vertex);
const auto position = grid_map::Position(v.x_, v.y_);
if (!gridMap.isInside(position)) {
return true; // treat space outside the map as being in collision
}
grid_map::Index id;
gridMap.getIndex(position, id);
occupancy = data(bindToRange(id.x(), 0, nRows), bindToRange(id.y(), 0, nCols));
grid_map::Index idx;
gridMap.getIndex(position, idx);
// TODO(christoph): What is the value for out of the map? Not working correctly for x-direction
occupancy = data(bindToRange(idx.x(), 0, nRows), bindToRange(idx.y(), 0, nCols));
} catch (const std::out_of_range& e) {
continue; // TODO at the moment return traversable for out of bounds case
// return true; // would assume all points out of bounds to be intraversable
Expand All @@ -168,42 +169,47 @@ bool isInCollision(const SE2state& state, const std::vector<Vertex>& footprint,
return false;
}

// TODO Not working with updated state space bounds
// bool isTraversable(const SE2state& state, const std::vector<Vertex>& footprint, const grid_map::GridMap& gridMap,
// const std::string& traversabilityLayer, const double traversabilityThreshold) {
// const double Cos = std::cos(state.yaw_);
// const double Sin = std::sin(state.yaw_);
// const double dx = state.x_;
// const double dy = state.y_;
// auto transformOperator = [Cos, Sin, dx, dy](const Vertex& v) -> Vertex {
// return Vertex{Cos * v.x_ - Sin * v.y_ + dx, Sin * v.x_ + Cos * v.y_ + dy};
// };
// const auto& data = gridMap.get(traversabilityLayer);
// for (const auto& vertex : footprint) {
// double traversability = 1.0;
// try {
// // Translate and rotate to current state
// const auto v = transformOperator(vertex);
// grid_map::Index id;
// gridMap.getIndex(grid_map::Position(v.x_, v.y_), id);
// traversability = data(id.x(), id.y());
// } catch (const std::out_of_range& e) {
// continue; // TODO at the moment return traversable for out of bounds case
// }
//
// // ignore nans since they might come from faulty
// // perception pipeline
// if (std::isnan(traversability)) {
// continue;
// }
//
// if (traversability < traversabilityThreshold) {
// return false;
// }
// }
//
// return true;
//}
bool isTraversable(const SE2state& state, const std::vector<Vertex>& footprint, const grid_map::GridMap& gridMap,
const std::string& traversabilityLayer, const double traversabilityThreshold) {
const double Cos = std::cos(state.yaw_);
const double Sin = std::sin(state.yaw_);
const double dx = state.x_;
const double dy = state.y_;

auto transformOperator = [Cos, Sin, dx, dy](const Vertex& v) -> Vertex {
return Vertex{Cos * v.x_ - Sin * v.y_ + dx, Sin * v.x_ + Cos * v.y_ + dy};
};

const auto& data = gridMap.get(traversabilityLayer);
const int nRows = data.rows();
const int nCols = data.cols();
for (const auto& vertex : footprint) {
double traversability = 1.0;
try {
// Translate and rotate to current state
const auto v = transformOperator(vertex);
const auto position = grid_map::Position(v.x_, v.y_);
grid_map::Index idx;
gridMap.getIndex(position, idx);
// TODO(christoph): What is the value for out of the map? Not working correctly.
traversability = data(bindToRange(idx.x(), 0, nRows), bindToRange(idx.y(), 0, nCols));
} catch (const std::out_of_range& e) {
continue; // TODO at the moment return traversable for out of bounds case
}

// ignore nans since they might come from faulty
// perception pipeline
if (std::isnan(traversability)) {
continue;
}

if (traversability < traversabilityThreshold) {
return false;
}
}

return true;
}

bool isTraversableIterator(const SE2state& state, const RobotFootprint& footprint, const grid_map::GridMap& gridMap,
const std::string& traversabilityLayer, const double traversabilityThreshold) {
Expand Down