Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
|
LookupGrid class implements a fast occupancy grid creation and intersection data structure. The user provides 2d min/max bounds on the grid as well as cell side length (cells are always square). The user can then add points into the grid. Cells which contain points are marked as occupied. Once the grid is populated, intersections can be checked against. If the queried point lands in an occupied cell the intersection is reported as true. More...
#include <lookup_grid.hpp>
Public Member Functions | |
LookupGrid () | |
Default constructor Note: This constructor is provided for convenience but users should normally use the constructor which takes a Config object. More... | |
LookupGrid (Config config) | |
Constructor. More... | |
Config | get_config () |
Return the current config. More... | |
bool | intersects (PointT point) const |
Checks if a point lies within an occupied cell of the grid. More... | |
void | insert (PointT point) |
Adds a point to the grid. The point must lie within the grid bounds. The cell which the point lies in is marked as occupied. More... | |
Protected Types | |
using | Hasher = autoware::common::geometry::spatial_hash::Config2d |
using | HashIndex = autoware::common::geometry::spatial_hash::Index |
Protected Attributes | |
Config | config_ |
Configuration. More... | |
Hasher | hasher_ |
Spatial hasher which defines the grid. More... | |
std::unordered_set< HashIndex > | occupied_cells_ |
The set of occupied cells identified by their hash index. More... | |
Static Protected Attributes | |
static constexpr size_t | PLACE_HOLDER_CAPACITY = 1 |
Static placeholder value for the Autoware.Auto Hasher in use which requires this value but does not utilize it. More... | |
LookupGrid class implements a fast occupancy grid creation and intersection data structure. The user provides 2d min/max bounds on the grid as well as cell side length (cells are always square). The user can then add points into the grid. Cells which contain points are marked as occupied. Once the grid is populated, intersections can be checked against. If the queried point lands in an occupied cell the intersection is reported as true.
PointT | The type of 2d point which the grid will be built from. Must have publicly accessible .x and .y members. |
Definition at line 37 of file lookup_grid.hpp.
|
protected |
Definition at line 40 of file lookup_grid.hpp.
|
protected |
Definition at line 41 of file lookup_grid.hpp.
|
inline |
Default constructor Note: This constructor is provided for convenience but users should normally use the constructor which takes a Config object.
Definition at line 63 of file lookup_grid.hpp.
|
inline |
Constructor.
config | The configuration for the grid. |
Definition at line 70 of file lookup_grid.hpp.
References approximate_intersection::Config::cell_side_length, approximate_intersection::Config::max_x, approximate_intersection::Config::max_y, approximate_intersection::Config::min_x, approximate_intersection::Config::min_y, and approximate_intersection::LookupGrid< PointT >::occupied_cells_.
|
inline |
Return the current config.
Definition at line 93 of file lookup_grid.hpp.
References approximate_intersection::LookupGrid< PointT >::config_.
|
inline |
Adds a point to the grid. The point must lie within the grid bounds. The cell which the point lies in is marked as occupied.
point | The point to add to the grid |
Definition at line 121 of file lookup_grid.hpp.
References approximate_intersection::LookupGrid< PointT >::hasher_, approximate_intersection::LookupGrid< PointT >::occupied_cells_, and process_traj_logs::point.
|
inline |
Checks if a point lies within an occupied cell of the grid.
point | The point to check for intersection |
Definition at line 104 of file lookup_grid.hpp.
References approximate_intersection::LookupGrid< PointT >::hasher_, approximate_intersection::LookupGrid< PointT >::occupied_cells_, and process_traj_logs::point.
|
protected |
Configuration.
Definition at line 45 of file lookup_grid.hpp.
Referenced by approximate_intersection::LookupGrid< PointT >::get_config().
|
protected |
Spatial hasher which defines the grid.
Definition at line 48 of file lookup_grid.hpp.
Referenced by approximate_intersection::LookupGrid< PointT >::insert(), and approximate_intersection::LookupGrid< PointT >::intersects().
|
protected |
The set of occupied cells identified by their hash index.
Definition at line 51 of file lookup_grid.hpp.
Referenced by approximate_intersection::LookupGrid< PointT >::LookupGrid(), approximate_intersection::LookupGrid< PointT >::insert(), and approximate_intersection::LookupGrid< PointT >::intersects().
|
staticconstexprprotected |
Static placeholder value for the Autoware.Auto Hasher in use which requires this value but does not utilize it.
Definition at line 54 of file lookup_grid.hpp.