Classes | |
class | BaseCostmapToDynamicObstacles |
class | BaseCostmapToPolygons |
This abstract class defines the interface for plugins that convert the costmap into polygon types. More... | |
class | CostmapToDynamicObstacles |
This class converts the costmap_2d into dynamic obstacles. More... | |
class | CostmapToLinesDBSMCCH |
This class converts the costmap_2d into a set of lines (and points) More... | |
class | CostmapToLinesDBSRANSAC |
This class converts the costmap_2d into a set of lines (and points) More... | |
class | CostmapToPolygonsDBSConcaveHull |
This class converts the costmap_2d into a set of non-convex polygons (and points) More... | |
class | CostmapToPolygonsDBSMCCH |
This class converts the costmap_2d into a set of convex polygons (and points) More... | |
Typedefs | |
typedef CostmapToLinesDBSMCCH | CL |
typedef boost::shared_ptr< const ObstacleArrayMsg > | ObstacleArrayConstPtr |
Typedef for a shared dynamic obstacle container (read-only access) More... | |
typedef boost::shared_ptr< ObstacleArrayMsg > | ObstacleArrayPtr |
Typedef for a shared dynamic obstacle container. More... | |
typedef boost::shared_ptr< const std::vector< geometry_msgs::Polygon > > | PolygonContainerConstPtr |
Typedef for a shared polygon container (read-only access) More... | |
typedef boost::shared_ptr< std::vector< geometry_msgs::Polygon > > | PolygonContainerPtr |
Typedef for a shared polygon container. More... | |
Functions | |
template<typename Point , typename LinePoint > | |
double | computeDistanceToLine (const Point &point, const LinePoint &line_pt1, const LinePoint &line_pt2) |
Calculate the distance between a point and a straight line (with infinite length) More... | |
template<typename Point , typename LinePoint > | |
double | computeDistanceToLineSegment (const Point &point, const LinePoint &line_start, const LinePoint &line_end, bool *is_inbetween=NULL) |
Calculate the distance between a point and a straight line segment. More... | |
template<typename Point , typename LinePoint > | |
double | computeSquaredDistanceToLineSegment (const Point &point, const LinePoint &line_start, const LinePoint &line_end, bool *is_inbetween=NULL) |
Calculate the squared distance between a point and a straight line segment. More... | |
template<typename Point1 , typename Point2 > | |
bool | isApprox2d (const Point1 &pt1, const Point2 &pt2, double threshold) |
Check if two points are approximately defining the same one. More... | |
bool | isXCoordinateSmaller (const CostmapToPolygonsDBSMCCH::KeyPoint &p1, const CostmapToPolygonsDBSMCCH::KeyPoint &p2) |
template<typename Point1 , typename Point2 > | |
double | norm2d (const Point1 &pt1, const Point2 &pt2) |
Calculate the distance between two 2d points. More... | |
bool | sort_keypoint_x (const std::size_t &i, const std::size_t &j, const std::vector< CL::KeyPoint > &cluster) |
bool | sort_keypoint_y (const std::size_t &i, const std::size_t &j, const std::vector< CL::KeyPoint > &cluster) |
Definition at line 122 of file costmap_to_lines_convex_hull.cpp.
typedef boost::shared_ptr< const ObstacleArrayMsg > costmap_converter::ObstacleArrayConstPtr |
Typedef for a shared dynamic obstacle container (read-only access)
Definition at line 57 of file costmap_converter_interface.h.
typedef boost::shared_ptr<ObstacleArrayMsg> costmap_converter::ObstacleArrayPtr |
Typedef for a shared dynamic obstacle container.
Definition at line 55 of file costmap_converter_interface.h.
typedef boost::shared_ptr< const std::vector<geometry_msgs::Polygon> > costmap_converter::PolygonContainerConstPtr |
Typedef for a shared polygon container (read-only access)
Definition at line 62 of file costmap_converter_interface.h.
typedef boost::shared_ptr< std::vector<geometry_msgs::Polygon> > costmap_converter::PolygonContainerPtr |
Typedef for a shared polygon container.
Definition at line 60 of file costmap_converter_interface.h.
|
inline |
Calculate the distance between a point and a straight line (with infinite length)
point | generic 2D point type defining the reference point |
line_pt1 | generic 2D point as part of the line |
line_pt2 | generic 2D point as part of the line |
Point | generic point type that should provide x and y member fiels. |
LinePoint | generic point type that should provide x and y member fiels. |
|
inline |
Calculate the distance between a point and a straight line segment.
point | generic 2D point type defining the reference point | |
line_start | generic 2D point type defining the start of the line | |
line_end | generic 2D point type defining the end of the line | |
[out] | is_inbetween | write true , if the point is placed inbetween start and end [optional] |
Point | generic point type that should provide x and y member fiels. |
LinePoint | generic point type that should provide x and y member fiels. |
|
inline |
Calculate the squared distance between a point and a straight line segment.
point | generic 2D point type defining the reference point | |
line_start | generic 2D point type defining the start of the line | |
line_end | generic 2D point type defining the end of the line | |
[out] | is_inbetween | write true , if the point is placed inbetween start and end [optional] |
Point | generic point type that should provide x and y member fiels. |
LinePoint | generic point type that should provide x and y member fiels. |
|
inline |
Check if two points are approximately defining the same one.
pt1 | generic 2D point |
pt2 | generic 2D point |
threshold | define the minimum threshold |pt1.x-pt2.y| < tresh && |pt1.y-pt2.y| < tresh |
Point1 | generic point type that should provide x and y member fiels. |
Point2 | generic point type that should provide x and y member fiels. |
true
, if similar, false
otherwise bool costmap_converter::isXCoordinateSmaller | ( | const CostmapToPolygonsDBSMCCH::KeyPoint & | p1, |
const CostmapToPolygonsDBSMCCH::KeyPoint & | p2 | ||
) |
Definition at line 314 of file costmap_to_polygons.cpp.
|
inline |
Calculate the distance between two 2d points.
pt1 | generic 2D point |
pt2 | generic 2D point |
Point1 | generic point type that should provide x and y member fiels. |
Point2 | generic point type that should provide x and y member fiels. |
bool costmap_converter::sort_keypoint_x | ( | const std::size_t & | i, |
const std::size_t & | j, | ||
const std::vector< CL::KeyPoint > & | cluster | ||
) |
Definition at line 123 of file costmap_to_lines_convex_hull.cpp.
bool costmap_converter::sort_keypoint_y | ( | const std::size_t & | i, |
const std::size_t & | j, | ||
const std::vector< CL::KeyPoint > & | cluster | ||
) |
Definition at line 125 of file costmap_to_lines_convex_hull.cpp.