#include <math.h>#include <algorithm>#include <vector>#include <geometry_msgs/Point.h>

Go to the source code of this file.
Functions | |
| double | distance (double x0, double y0, double x1, double y1) |
| double | distanceToLine (double pX, double pY, double x0, double y0, double x1, double y1) |
| bool | intersects (std::vector< geometry_msgs::Point > &polygon, float testx, float testy) |
| bool | intersects (std::vector< geometry_msgs::Point > &polygon1, std::vector< geometry_msgs::Point > &polygon2) |
| double | sign (double x) |
| Return -1 if x < 0, +1 otherwise. | |
| double | sign0 (double x) |
| Same as sign(x) but returns 0 if x is 0. | |
| double distance | ( | double | x0, |
| double | y0, | ||
| double | x1, | ||
| double | y1 | ||
| ) | [inline] |
Definition at line 58 of file costmap_math.h.
| double distanceToLine | ( | double | pX, |
| double | pY, | ||
| double | x0, | ||
| double | y0, | ||
| double | x1, | ||
| double | y1 | ||
| ) |
Definition at line 32 of file costmap_math.cpp.
| bool intersects | ( | std::vector< geometry_msgs::Point > & | polygon, |
| float | testx, | ||
| float | testy | ||
| ) |
Definition at line 64 of file costmap_math.cpp.
| bool intersects | ( | std::vector< geometry_msgs::Point > & | polygon1, |
| std::vector< geometry_msgs::Point > & | polygon2 | ||
| ) |
Definition at line 86 of file costmap_math.cpp.
| double sign | ( | double | x | ) | [inline] |
Return -1 if x < 0, +1 otherwise.
Definition at line 47 of file costmap_math.h.
| double sign0 | ( | double | x | ) | [inline] |
Same as sign(x) but returns 0 if x is 0.
Definition at line 53 of file costmap_math.h.