#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 <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 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) |
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) |
template<class T > | |
ostream & | operator<< (ostream &str, const vector< T > &s) |
ostream & | operator<< (ostream &str, const gm::Point &p) |
bool | geometry_msgs::operator== (const Polygon &p1, const Polygon &p2) |
bool | samePath (const Path &p1, const Path &p2) |
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, CoordinateConversions) | |
TEST (GridUtils, RayTrace) | |
TEST (GridUtils, GridOverlay) | |
TEST (GridUtils, ShortestPath) | |
TEST (GridUtils, InflateObstacles) | |
TEST (GridUtils, CombineGrids) | |
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 |
typedef boost::shared_ptr<nm::OccupancyGrid const> GridConstPtr |
Definition at line 62 of file test_grid_utils.cpp.
typedef boost::shared_ptr<nm::OccupancyGrid> GridPtr |
Definition at line 61 of file test_grid_utils.cpp.
typedef vector<Cell> Path |
Definition at line 60 of file test_grid_utils.cpp.
double angle | ( | const double | x1, |
const double | y1, | ||
const double | x2, | ||
const double | y2 | ||
) |
Definition at line 150 of file test_grid_utils.cpp.
bool approxEqual | ( | const double | x, |
const double | y | ||
) |
Definition at line 74 of file test_grid_utils.cpp.
gm::Point lastPoint | ( | const nm::MapMetaData & | info, |
const gu::RayTraceIterRange & | r | ||
) |
Definition at line 203 of file test_grid_utils.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 542 of file test_grid_utils.cpp.
Definition at line 117 of file test_grid_utils.cpp.
gm::Point32 makePoint32 | ( | const double | x, |
const double | y | ||
) |
Definition at line 125 of file test_grid_utils.cpp.
Definition at line 156 of file test_grid_utils.cpp.
double norm | ( | const double | x, |
const double | y | ||
) |
Definition at line 133 of file test_grid_utils.cpp.
ostream& operator<< | ( | ostream & | str, |
const vector< T > & | s | ||
) |
Definition at line 100 of file test_grid_utils.cpp.
ostream& operator<< | ( | ostream & | str, |
const gm::Point & | p | ||
) |
Definition at line 111 of file test_grid_utils.cpp.
Definition at line 64 of file test_grid_utils.cpp.
void setOccupied | ( | nm::OccupancyGrid * | g, |
const unsigned | x, | ||
const unsigned | y | ||
) |
Definition at line 334 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 445 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , |
CoordinateConversions | |||
) |
Definition at line 168 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , |
RayTrace | |||
) |
Definition at line 213 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , |
GridOverlay | |||
) |
Definition at line 254 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , |
ShortestPath | |||
) |
Definition at line 339 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , |
InflateObstacles | |||
) |
Definition at line 452 of file test_grid_utils.cpp.
TEST | ( | GridUtils | , |
CombineGrids | |||
) |
Definition at line 481 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 438 of file test_grid_utils.cpp.
const double PI = 3.14159265 |
Definition at line 55 of file test_grid_utils.cpp.
const double TOL = 1e-6 |
Definition at line 57 of file test_grid_utils.cpp.