44 #include <Eigen/StdVector> 45 #include <Eigen/Geometry> 49 #include <boost/shared_ptr.hpp> 50 #include <boost/pointer_cast.hpp> 52 #include <geometry_msgs/Polygon.h> 53 #include <geometry_msgs/TwistWithCovariance.h> 54 #include <geometry_msgs/QuaternionStamped.h> 93 virtual const Eigen::Vector2d&
getCentroid()
const = 0;
113 virtual bool checkCollision(
const Eigen::Vector2d& position,
double min_dist)
const = 0;
137 virtual double getMinimumDistance(
const Eigen::Vector2d& line_start,
const Eigen::Vector2d& line_end)
const = 0;
151 virtual Eigen::Vector2d
getClosestPoint(
const Eigen::Vector2d& position)
const = 0;
215 const geometry_msgs::Quaternion& orientation)
219 vel.coeffRef(0) = velocity.twist.linear.x;
220 vel.coeffRef(1) = velocity.twist.linear.y;
224 if (vel.norm() < 0.001)
236 const geometry_msgs::QuaternionStamped& orientation)
262 virtual void toPolygonMsg(geometry_msgs::Polygon& polygon) = 0;
273 twistWithCovariance.twist.linear.x = 0;
274 twistWithCovariance.twist.linear.y = 0;
288 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
347 double t = a.dot(b)/a.dot(a);
350 Eigen::Vector2d nearest_point = line_start + a*t;
360 return (position-pos_).norm();
414 return std::complex<double>(pos_[0],pos_[1]);
418 const Eigen::Vector2d&
position()
const {
return pos_;}
420 double&
x() {
return pos_.coeffRef(0);}
421 const double&
x()
const {
return pos_.coeffRef(0);}
422 double&
y() {
return pos_.coeffRef(1);}
423 const double&
y()
const {
return pos_.coeffRef(1);}
428 polygon.points.resize(1);
429 polygon.points.front().x = pos_.x();
430 polygon.points.front().y = pos_.y();
431 polygon.points.front().z = 0;
440 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
491 double t = a.dot(b)/a.dot(a);
494 Eigen::Vector2d nearest_point = line_start + a*t;
504 return (position-pos_).norm() - radius_;
522 return pos_ + radius_*(position-pos_).
normalized();
558 return std::complex<double>(pos_[0],pos_[1]);
562 const Eigen::Vector2d&
position()
const {
return pos_;}
564 double&
x() {
return pos_.coeffRef(0);}
565 const double&
x()
const {
return pos_.coeffRef(0);}
566 double&
y() {
return pos_.coeffRef(1);}
567 const double&
y()
const {
return pos_.coeffRef(1);}
569 const double&
radius()
const {
return radius_;}
576 polygon.points.resize(1);
577 polygon.points.front().x = pos_.x();
578 polygon.points.front().y = pos_.y();
579 polygon.points.front().z = 0;
585 double radius_ = 0.0;
589 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
601 typedef std::vector<Eigen::Vector2d,Eigen::aligned_allocator<Eigen::Vector2d> >
VertexContainer;
619 :
Obstacle(), start_(line_start), end_(line_end)
706 return std::complex<double>(centroid_.x(), centroid_.y());
710 const Eigen::Vector2d&
start()
const {
return start_;}
711 void setStart(
const Eigen::Ref<const Eigen::Vector2d>& start) {start_ = start; calcCentroid();}
712 const Eigen::Vector2d&
end()
const {
return end_;}
713 void setEnd(
const Eigen::Ref<const Eigen::Vector2d>& end) {end_ = end; calcCentroid();}
718 polygon.points.resize(2);
719 polygon.points.front().x = start_.x();
720 polygon.points.front().y = start_.y();
722 polygon.points.back().x = end_.x();
723 polygon.points.back().y = end_.y();
724 polygon.points.back().z = polygon.points.front().z = 0;
737 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
757 centroid_.setConstant(NAN);
792 for (i = 0, j = noVertices()-1; i < noVertices(); j = i++)
794 if ( ((vertices_.at(i).y()>point.y()) != (vertices_.at(j).y()>point.y())) &&
795 (point.x() < (vertices_.at(j).x()-vertices_.at(i).x()) * (point.y()-vertices_.at(i).y()) / (vertices_.at(j).y()-vertices_.at(i).y()) + vertices_.at(i).x()) )
798 if (c>0)
return true;
824 virtual double getMinimumDistance(
const Eigen::Vector2d& line_start,
const Eigen::Vector2d& line_end)
const 836 virtual Eigen::Vector2d
getClosestPoint(
const Eigen::Vector2d& position)
const;
842 predictVertices(t, pred_vertices);
850 predictVertices(t, pred_vertices);
858 predictVertices(t, pred_vertices);
865 pred_vertices.resize(vertices_.size());
867 for (std::size_t i = 0; i < vertices_.size(); i++)
869 pred_vertices[i] = vertices_[i] + offset;
876 assert(finalized_ &&
"Finalize the polygon after all vertices are added.");
883 assert(finalized_ &&
"Finalize the polygon after all vertices are added.");
884 return std::complex<double>(centroid_.coeffRef(0), centroid_.coeffRef(1));
888 virtual void toPolygonMsg(geometry_msgs::Polygon& polygon);
906 vertices_.push_back(vertex);
919 vertices_.push_back(Eigen::Vector2d(x,y));
948 void fixPolygonClosure();
960 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
virtual void toPolygonMsg(geometry_msgs::Polygon &polygon)=0
Convert the obstacle to a polygon message.
virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end, double t) const
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity mo...
PointObstacle(const Eigen::Ref< const Eigen::Vector2d > &position)
Construct PointObstacle using a 2d position vector.
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > VertexContainer
Abbrev. for a container storing vertices (2d points defining the edge points of the polygon) ...
Eigen::Vector2d pos_
Store the center position of the CircularObstacle.
Implements a 2D circular obstacle (point obstacle plus radius)
bool isDynamic() const
Check if the obstacle is a moving with a (non-zero) velocity.
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.
virtual bool checkCollision(const Eigen::Vector2d &point, double min_dist) const
Check if a given point collides with the obstacle.
const double & x() const
Return the current y-coordinate of the obstacle (read-only)
virtual double getMinimumDistance(const Eigen::Vector2d &position) const
Get the minimum euclidean distance to the obstacle (point as reference)
virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d &position, double t) const
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity mo...
virtual double getMinimumDistance(const Point2dContainer &polygon) const
Get the minimum euclidean distance to the obstacle (polygon as reference)
void finalizePolygon()
Call finalizePolygon after the polygon is created with the help of pushBackVertex() methods...
virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d &position, double t) const =0
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity mo...
int noVertices() const
Get the number of vertices defining the polygon (the first vertex is counted once) ...
void setCentroidVelocity(const geometry_msgs::TwistWithCovariance &velocity, const geometry_msgs::Quaternion &orientation)
Set the 2d velocity (vx, vy) of the obstacle w.r.t to the centroid.
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...
const double & y() const
Return the current y-coordinate of the obstacle (read-only)
CircularObstacle()
Default constructor of the circular obstacle class.
virtual Eigen::Vector2d getClosestPoint(const Eigen::Vector2d &position) const =0
Get the closest point on the boundary of the obstacle w.r.t. a specified reference position...
virtual const Eigen::Vector2d & getCentroid() const =0
Get centroid coordinates of the obstacle.
void clearVertices()
Clear all vertices (Afterwards the polygon is not valid anymore)
virtual ~Obstacle()
Virtual destructor.
const Point2dContainer & vertices() const
Access vertices container (read-only)
PolygonObstacle(const Point2dContainer &vertices)
Construct polygon obstacle with a list of vertices.
PolygonObstacle()
Default constructor of the polygon obstacle class.
virtual const Eigen::Vector2d & getCentroid() const
Get centroid coordinates of the obstacle.
PointObstacle()
Default constructor of the point obstacle class.
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...
CircularObstacle(double x, double y, double radius)
Construct CircularObstacle using x- and y-center-coordinates and radius.
virtual std::complex< double > getCentroidCplx() const
Get centroid coordinates of the obstacle as complex number.
double distance_segment_to_segment_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)
Helper function to calculate the smallest distance between two line segments.
virtual double getMinimumSpatioTemporalDistance(const Point2dContainer &polygon, double t) const
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity mo...
virtual std::complex< double > getCentroidCplx() const
Get centroid coordinates of the obstacle as complex number.
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...
boost::shared_ptr< const Obstacle > ObstacleConstPtr
Abbrev. for shared obstacle const pointers.
PointObstacle(double x, double y)
Construct PointObstacle using x- and y-coordinates.
const double & x() const
Return the current y-coordinate of the obstacle (read-only)
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...
virtual const Eigen::Vector2d & getCentroid() const
Get centroid coordinates of the obstacle.
virtual void toTwistWithCovarianceMsg(geometry_msgs::TwistWithCovariance &twistWithCovariance)
LineObstacle(const Eigen::Ref< const Eigen::Vector2d > &line_start, const Eigen::Ref< const Eigen::Vector2d > &line_end)
Construct LineObstacle using 2d position vectors as start and end of the line.
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...
const double & y() const
Return the current y-coordinate of the obstacle (read-only)
Point2dContainer vertices_
Store vertices defining the polygon (.
virtual void predictCentroidConstantVelocity(double t, Eigen::Ref< Eigen::Vector2d > position) const
Predict position of the centroid assuming a constant velocity model.
Eigen::Vector2d & position()
Return the current position of the obstacle.
virtual double getMinimumDistance(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end) const
Get the minimum euclidean distance to the obstacle (line as reference)
LineObstacle()
Default constructor of the point obstacle class.
void setCentroidVelocity(const Eigen::Ref< const Eigen::Vector2d > &vel)
Set the 2d velocity (vx, vy) of the obstacle w.r.t to the centroid.
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
Abbrev. for a container storing 2d points.
virtual double getMinimumDistance(const Point2dContainer &polygon) const
Get the minimum euclidean distance to the obstacle (polygon as reference)
virtual void toPolygonMsg(geometry_msgs::Polygon &polygon)
Convert the obstacle to a polygon message.
virtual double getMinimumSpatioTemporalDistance(const Point2dContainer &polygon, double t) const
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity mo...
virtual std::complex< double > getCentroidCplx() const
Get centroid coordinates of the obstacle as complex number.
virtual void toPolygonMsg(geometry_msgs::Polygon &polygon)
Convert the obstacle to a polygon message.
Implements a polygon obstacle with an arbitrary number of vertices.
Implements a 2D line obstacle.
virtual void predictVertices(double t, Point2dContainer &pred_vertices) const
Obstacle()
Default constructor of the abstract obstacle class.
virtual double getMinimumDistance(const Eigen::Vector2d &position) const
Get the minimum euclidean distance to the obstacle (point as reference)
boost::shared_ptr< Obstacle > ObstaclePtr
Abbrev. for shared obstacle pointers.
TFSIMD_FORCE_INLINE Vector3 normalized() const
const Eigen::Vector2d & position() const
Return the current position of the obstacle (read-only)
Point2dContainer & vertices()
Access vertices container.
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 double getMinimumSpatioTemporalDistance(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end, double t) const
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity mo...
virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d &position, double t) const
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity mo...
const double & radius() const
Return the current radius of the obstacle.
virtual double getMinimumDistance(const Eigen::Vector2d &position) const
Get the minimum euclidean distance to the obstacle (point as reference)
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...
bool finalized_
Flat that keeps track if the polygon was finalized after adding all vertices.
virtual void predictCentroidConstantVelocity(double t, Eigen::Ref< Eigen::Vector2d > position) const
Predict position of the centroid assuming a constant velocity model.
virtual std::complex< double > getCentroidCplx() const =0
Get centroid coordinates of the obstacle as complex number.
virtual double getMinimumSpatioTemporalDistance(const Point2dContainer &polygon, double t) const
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity mo...
double & x()
Return the current x-coordinate of the obstacle.
virtual void toPolygonMsg(geometry_msgs::Polygon &polygon)
Convert the obstacle to a polygon message.
Implements a 2D point obstacle.
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
virtual double getMinimumDistance(const Eigen::Vector2d &position) const
Get the minimum euclidean distance to the obstacle (point as reference)
virtual bool checkCollision(const Eigen::Vector2d &position, double min_dist) const =0
Check if a given point collides with the obstacle.
virtual double getMinimumSpatioTemporalDistance(const Point2dContainer &polygon, double t) const
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity mo...
void pushBackVertex(const Eigen::Ref< const Eigen::Vector2d > &vertex)
Add a vertex to the polygon (edge-point)
virtual double getMinimumDistance(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end) const
Get the minimum euclidean distance to the obstacle (line as reference)
virtual double getMinimumDistance(const Eigen::Vector2d &position) const =0
Get the minimum euclidean distance to the obstacle (point as reference)
double & y()
Return the current x-coordinate of the obstacle.
double distance_point_to_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 calculate the distance between a line segment and a point.
const Eigen::Vector2d & end() const
void pushBackVertex(double x, double y)
Add a vertex to the polygon (edge-point)
double distance_polygon_to_polygon_2d(const Point2dContainer &vertices1, const Point2dContainer &vertices2)
Helper function to calculate the smallest distance between two closed polygons.
double distance_point_to_polygon_2d(const Eigen::Vector2d &point, const Point2dContainer &vertices)
Helper function to calculate the smallest distance between a point and a closed polygon.
Eigen::Vector2d centroid_velocity_
Store the corresponding velocity (vx, vy) of the centroid (zero, if _dynamic is true) ...
void setStart(const Eigen::Ref< const Eigen::Vector2d > &start)
void setCentroidVelocity(const geometry_msgs::TwistWithCovariance &velocity, const geometry_msgs::QuaternionStamped &orientation)
CircularObstacle(const Eigen::Ref< const Eigen::Vector2d > &position, double radius)
Construct CircularObstacle using a 2d center position vector and radius.
virtual double getMinimumDistance(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end) const
Get the minimum euclidean distance to the obstacle (line as reference)
const Eigen::Vector2d & start() const
Eigen::Vector2d & position()
Return the current position of the obstacle.
const Eigen::Vector2d & getCentroidVelocity() const
Get the obstacle velocity (vx, vy) (w.r.t. to the centroid)
virtual std::complex< double > getCentroidCplx() const
Get centroid coordinates of the obstacle as complex number.
virtual const Eigen::Vector2d & getCentroid() const
Get centroid coordinates of the obstacle.
virtual double getMinimumDistance(const Point2dContainer &polygon) const
Get the minimum euclidean distance to the obstacle (polygon as reference)
double distance_segment_to_polygon_2d(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end, const Point2dContainer &vertices)
Helper function to calculate the smallest distance between a line segment and a closed polygon...
virtual double getMinimumDistance(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end) const
Get the minimum euclidean distance to the obstacle (line as reference)
Eigen::Vector2d centroid_
Store the centroid coordinates of the polygon (.
double & radius()
Return the current radius of the obstacle.
virtual bool checkCollision(const Eigen::Vector2d &point, double min_dist) const
Check if a given point collides with the obstacle.
Eigen::Vector2d pos_
Store the position of the PointObstacle.
const Eigen::Vector2d & position() const
Return the current position of the obstacle (read-only)
virtual bool checkCollision(const Eigen::Vector2d &point, double min_dist) const
Check if a given point collides with the obstacle.
Eigen::Vector2d centroid_
virtual bool checkLineIntersection(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end, double min_dist=0) const =0
Check if a given line segment between two points intersects with the obstacle (and additionally keeps...
bool dynamic_
Store flag if obstacle is dynamic (resp. a moving obstacle)
virtual double getMinimumDistance(const Point2dContainer &polygon) const
Get the minimum euclidean distance to the obstacle (polygon as reference)
virtual void predictCentroidConstantVelocity(double t, Eigen::Ref< Eigen::Vector2d > position) const
Predict position of the centroid assuming a constant velocity model.
virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d &position, double t) const
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity mo...
virtual const Eigen::Vector2d & getCentroid() const
Get centroid coordinates of the obstacle.
virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end, double t) const
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity mo...
LineObstacle(double x1, double y1, double x2, double y2)
Construct LineObstacle using start and end coordinates.
virtual bool checkCollision(const Eigen::Vector2d &point, double min_dist) const
Check if a given point collides with the obstacle.
virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d &position, double t) const
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity mo...
virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end, double t) const
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity mo...
double & x()
Return the current x-coordinate of the obstacle.
double & y()
Return the current x-coordinate of the obstacle.
Abstract class that defines the interface for modelling obstacles.
void setEnd(const Eigen::Ref< const Eigen::Vector2d > &end)