#include <vector>#include <numeric>#include <geometry_msgs/Point32.h>#include <geometry_msgs/Polygon.h>#include <sensor_msgs/LaserScan.h>#include <lama_common/point.h>#include <lama_common/is_sorted.h>

Go to the source code of this file.
Namespaces | |
| namespace | lama_common |
Functions | |
| geometry_msgs::Polygon | lama_common::centeredPolygon (const geometry_msgs::Polygon &polygon) |
| geometry_msgs::Polygon | lama_common::centeredPolygon (const geometry_msgs::Polygon &polygon, double &dx, double &dy) |
| void | lama_common::centerPolygon (geometry_msgs::Polygon &polygon) |
| void | lama_common::centerPolygon (geometry_msgs::Polygon &polygon, double &dx, double &dy) |
| template<typename T > | |
| double | lama_common::getLength (const vector< T > &pts) |
| template<typename T > | |
| vector< double > | lama_common::getLengths (const vector< T > &pts) |
| bool | lama_common::isClosed (const geometry_msgs::Polygon &poly, double max_frontier_width) |
| geometry_msgs::Polygon | lama_common::normalizedPolygon (const geometry_msgs::Polygon &poly, bool &normalized) |
| bool | lama_common::normalizePolygon (geometry_msgs::Polygon &poly) |
| template<typename T > | |
| vector< T > | lama_common::resamplePolygon (const vector< T > &polygon, unsigned int sample_count, double &delta) |
| template<> | |
| vector< Point32 > | lama_common::resamplePolygon< Point32 > (const vector< Point32 > &polygon, unsigned int sample_count, double &delta) |
| template<typename T > | |
| vector< T > | lama_common::scanToPolygon (const sensor_msgs::LaserScan &scan) |