Classes | Typedefs | Functions
costmap_converter Namespace Reference

Classes

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)
typedef boost::shared_ptr
< ObstacleArrayMsg > 
ObstacleArrayPtr
 Typedef for a shared dynamic obstacle container.
typedef boost::shared_ptr
< const std::vector
< geometry_msgs::Polygon > > 
PolygonContainerConstPtr
 Typedef for a shared polygon container (read-only access)
typedef boost::shared_ptr
< std::vector
< geometry_msgs::Polygon > > 
PolygonContainerPtr
 Typedef for a shared polygon container.

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)
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.
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.
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.
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)

Typedef Documentation

Definition at line 133 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.


Function Documentation

template<typename Point , typename LinePoint >
double costmap_converter::computeDistanceToLine ( const Point &  point,
const LinePoint &  line_pt1,
const LinePoint &  line_pt2 
) [inline]

Calculate the distance between a point and a straight line (with infinite length)

Parameters:
pointgeneric 2D point type defining the reference point
line_pt1generic 2D point as part of the line
line_pt2generic 2D point as part of the line
Template Parameters:
Pointgeneric point type that should provide x and y member fiels.
LinePointgeneric point type that should provide x and y member fiels.
Returns:
(minimum) euclidean distance to the line segment

Definition at line 58 of file misc.h.

template<typename Point , typename LinePoint >
double costmap_converter::computeDistanceToLineSegment ( const Point &  point,
const LinePoint &  line_start,
const LinePoint &  line_end,
bool *  is_inbetween = NULL 
) [inline]

Calculate the distance between a point and a straight line segment.

Parameters:
pointgeneric 2D point type defining the reference point
line_startgeneric 2D point type defining the start of the line
line_endgeneric 2D point type defining the end of the line
[out]is_inbetweenwrite true, if the point is placed inbetween start and end [optional]
Template Parameters:
Pointgeneric point type that should provide x and y member fiels.
LinePointgeneric point type that should provide x and y member fiels.
Returns:
(minimum) euclidean distance to the line segment

Definition at line 83 of file misc.h.

template<typename Point1 , typename Point2 >
bool costmap_converter::isApprox2d ( const Point1 &  pt1,
const Point2 &  pt2,
double  threshold 
) [inline]

Check if two points are approximately defining the same one.

Parameters:
pt1generic 2D point
pt2generic 2D point
thresholddefine the minimum threshold |pt1.x-pt2.y| < tresh && |pt1.y-pt2.y| < tresh
Template Parameters:
Point1generic point type that should provide x and y member fiels.
Point2generic point type that should provide x and y member fiels.
Returns:
true, if similar, false otherwise

Definition at line 132 of file misc.h.

bool costmap_converter::isXCoordinateSmaller ( const CostmapToPolygonsDBSMCCH::KeyPoint &  p1,
const CostmapToPolygonsDBSMCCH::KeyPoint &  p2 
)

Definition at line 227 of file costmap_to_polygons.cpp.

template<typename Point1 , typename Point2 >
double costmap_converter::norm2d ( const Point1 &  pt1,
const Point2 &  pt2 
) [inline]

Calculate the distance between two 2d points.

Parameters:
pt1generic 2D point
pt2generic 2D point
Template Parameters:
Point1generic point type that should provide x and y member fiels.
Point2generic point type that should provide x and y member fiels.
Returns:
euclidean distance to the line segment

Definition at line 117 of file misc.h.

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 134 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 136 of file costmap_to_lines_convex_hull.cpp.



costmap_converter
Author(s): Christoph Rösmann , Franz Albers , Otniel Rinaldo
autogenerated on Wed Sep 20 2017 03:00:37