62 ROS_WARN(
"PolygonObstacle::calcCentroid(): number of vertices is empty. the resulting centroid is a vector of NANs.");
145 double dist = (new_pt-position).norm();
146 Eigen::Vector2d closest_pt = new_pt;
152 double new_dist = (new_pt-position).norm();
161 double new_dist = (new_pt-position).norm();
173 ROS_ERROR(
"PolygonObstacle::getClosestPoint() cannot find any closest point. Polygon ill-defined?");
174 return Eigen::Vector2d::Zero();
199 for (std::size_t i=0; i<
vertices_.size(); ++i)
203 polygon.points[i].z = 0;
bool check_line_segments_intersection_2d(const Eigen::Ref< const Eigen::Vector2d > &line1_start, const Eigen::Ref< const Eigen::Vector2d > &line1_end, const Eigen::Ref< const Eigen::Vector2d > &line2_start, const Eigen::Ref< const Eigen::Vector2d > &line2_end, Eigen::Vector2d *intersection=NULL)
Helper function to check whether two line segments intersects.
int noVertices() const
Get the number of vertices defining the polygon (the first vertex is counted once) ...
virtual void toPolygonMsg(geometry_msgs::Polygon &polygon)
Convert the obstacle to a polygon message.
Point2dContainer vertices_
Store vertices defining the polygon (.
virtual Eigen::Vector2d getClosestPoint(const Eigen::Vector2d &position) const
Get the closest point on the boundary of the obstacle w.r.t. a specified reference position...
void fixPolygonClosure()
Check if the current polygon contains the first vertex twice (as start and end) and in that case eras...
Eigen::Vector2d closest_point_on_line_segment_2d(const Eigen::Ref< const Eigen::Vector2d > &point, const Eigen::Ref< const Eigen::Vector2d > &line_start, const Eigen::Ref< const Eigen::Vector2d > &line_end)
Helper function to obtain the closest point on a line segment w.r.t. a reference point.
virtual bool checkLineIntersection(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end, double min_dist=0) const
Check if a given line segment between two points intersects with the obstacle (and additionally keeps...
void calcCentroid()
Compute the centroid of the polygon (called inside finalizePolygon())
Eigen::Vector2d centroid_
Store the centroid coordinates of the polygon (.