$search
#include <occupancy_grid_utils/ray_tracer.h>
#include <occupancy_grid_utils/exceptions.h>
#include <occupancy_grid_utils/shortest_path.h>
#include <occupancy_grid_utils/combine_grids.h>
#include <occupancy_grid_utils/geometry.h>
#include <gtest/gtest.h>
#include <tf/transform_datatypes.h>
#include <ros/ros.h>
#include <iostream>
#include <boost/foreach.hpp>
#include <boost/bind.hpp>
#include <boost/assign.hpp>
#include <cmath>
Go to the source code of this file.
Classes | |
struct | CloseTo |
Namespaces | |
namespace | geometry_msgs |
Typedefs | |
typedef set< Cell > | Cells |
typedef boost::shared_ptr < nm::OccupancyGrid const > | GridConstPtr |
typedef boost::shared_ptr < nm::OccupancyGrid > | GridPtr |
typedef vector< Cell > | Path |
Functions | |
double | angle (const double x1, const double y1, const double x2, const double y2) |
bool | approxEqual (const double x, const double y) |
float | dist (const gu::DistanceField &d, int x, int y) |
template<class T > | |
bool | equalSets (const set< T > &s1, const set< T > &s2) |
gm::Point | lastPoint (const nm::MapMetaData &info, const gu::RayTraceIterRange &r) |
int | main (int argc, char **argv) |
gm::Point | makePoint (const double x, const double y) |
gm::Point32 | makePoint32 (const double x, const double y) |
gm::Pose | makePose (const double x, const double y, const double theta) |
double | norm (const double x, const double y) |
bool | not_pred (const Cell &c) |
ostream & | operator<< (ostream &str, const gm::Point &p) |
template<class T > | |
ostream & | operator<< (ostream &str, const set< T > &s) |
template<class T > | |
ostream & | operator<< (ostream &str, const vector< T > &s) |
bool | geometry_msgs::operator== (const Polygon &p1, const Polygon &p2) |
bool | pred (const Cell &c) |
bool | samePath (const Path &p1, const Path &p2) |
void | setOccupied (GridPtr g, const unsigned x, const unsigned y) |
void | setOccupied (nm::OccupancyGrid *g, const unsigned x, const unsigned y) |
void | setVal (nm::OccupancyGrid *g, const gu::coord_t x, const gu::coord_t y, const int v) |
TEST (GridUtils, CombineGrids) | |
TEST (GridUtils, Geometry) | |
TEST (GridUtils, InflateObstacles) | |
TEST (GridUtils, ShortestPath) | |
TEST (GridUtils, SimulateScan) | |
TEST (GridUtils, GridOverlay) | |
TEST (GridUtils, RayTrace) | |
TEST (GridUtils, DistanceField) | |
TEST (GridUtils, CoordinateConversions) | |
int | val (const nm::OccupancyGrid &g, const gu::coord_t x, const gu::coord_t y) |
Variables | |
const double | PI = 3.14159265 |
const double | TOL = 1e-6 |
Definition at line 64 of file test_grid_utils.cpp.
typedef boost::shared_ptr<nm::OccupancyGrid const> GridConstPtr |
Definition at line 66 of file test_grid_utils.cpp.
typedef boost::shared_ptr<nm::OccupancyGrid> GridPtr |
Definition at line 65 of file test_grid_utils.cpp.
Definition at line 63 of file test_grid_utils.cpp.
double angle | ( | const double | x1, | |
const double | y1, | |||
const double | x2, | |||
const double | y2 | |||
) |
Definition at line 188 of file test_grid_utils.cpp.
bool approxEqual | ( | const double | x, | |
const double | y | |||
) |
Definition at line 104 of file test_grid_utils.cpp.
float dist | ( | const gu::DistanceField & | d, | |
int | x, | |||
int | y | |||
) |
Definition at line 203 of file test_grid_utils.cpp.
bool equalSets | ( | const set< T > & | s1, | |
const set< T > & | s2 | |||
) | [inline] |
Definition at line 89 of file test_grid_utils.cpp.
gm::Point lastPoint | ( | const nm::MapMetaData & | info, | |
const gu::RayTraceIterRange & | r | |||
) |
Definition at line 271 of file test_grid_utils.cpp.
int main | ( | int | argc, | |
char ** | argv | |||
) |
Definition at line 712 of file test_grid_utils.cpp.
gm::Point makePoint | ( | const double | x, | |
const double | y | |||
) |
Definition at line 155 of file test_grid_utils.cpp.
gm::Point32 makePoint32 | ( | const double | x, | |
const double | y | |||
) |
Definition at line 163 of file test_grid_utils.cpp.
gm::Pose makePose | ( | const double | x, | |
const double | y, | |||
const double | theta | |||
) |
Definition at line 194 of file test_grid_utils.cpp.
double norm | ( | const double | x, | |
const double | y | |||
) |
Definition at line 171 of file test_grid_utils.cpp.
bool not_pred | ( | const Cell & | c | ) |
Definition at line 600 of file test_grid_utils.cpp.
ostream& operator<< | ( | ostream & | str, | |
const gm::Point & | p | |||
) |
Definition at line 149 of file test_grid_utils.cpp.
ostream& operator<< | ( | ostream & | str, | |
const set< T > & | s | |||
) | [inline] |
Definition at line 139 of file test_grid_utils.cpp.
ostream& operator<< | ( | ostream & | str, | |
const vector< T > & | s | |||
) | [inline] |
Definition at line 129 of file test_grid_utils.cpp.
bool pred | ( | const Cell & | c | ) |
Definition at line 590 of file test_grid_utils.cpp.
Definition at line 68 of file test_grid_utils.cpp.
void setOccupied | ( | GridPtr | g, | |
const unsigned | x, | |||
const unsigned | y | |||
) |
Definition at line 83 of file test_grid_utils.cpp.
void setOccupied | ( | nm::OccupancyGrid * | g, | |
const unsigned | x, | |||
const unsigned | y | |||
) |
Definition at line 78 of file test_grid_utils.cpp.
void setVal | ( | nm::OccupancyGrid * | g, | |
const gu::coord_t | x, | |||
const gu::coord_t | y, | |||
const int | v | |||
) |
Definition at line 549 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , | |
CombineGrids | ||||
) |
Definition at line 647 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , | |
Geometry | ||||
) |
Definition at line 605 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , | |
InflateObstacles | ||||
) |
Definition at line 557 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , | |
ShortestPath | ||||
) |
Definition at line 441 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , | |
SimulateScan | ||||
) |
Definition at line 402 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , | |
GridOverlay | ||||
) |
Definition at line 322 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , | |
RayTrace | ||||
) |
Definition at line 281 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , | |
DistanceField | ||||
) |
Definition at line 245 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , | |
CoordinateConversions | ||||
) |
Definition at line 209 of file test_grid_utils.cpp.
int val | ( | const nm::OccupancyGrid & | g, | |
const gu::coord_t | x, | |||
const gu::coord_t | y | |||
) |
Definition at line 542 of file test_grid_utils.cpp.
const double PI = 3.14159265 |
Definition at line 58 of file test_grid_utils.cpp.
const double TOL = 1e-6 |
Definition at line 60 of file test_grid_utils.cpp.