40 #ifndef ROBOT_FOOTPRINT_MODEL_H 41 #define ROBOT_FOOTPRINT_MODEL_H 45 #include <visualization_msgs/Marker.h> 103 virtual void visualizeRobot(
const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers,
const std_msgs::ColorRGBA& color)
const {}
115 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
237 virtual void visualizeRobot(
const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers,
const std_msgs::ColorRGBA& color)
const 240 visualization_msgs::Marker& marker = markers.back();
241 marker.type = visualization_msgs::Marker::CYLINDER;
243 marker.scale.x = marker.scale.y = 2*radius_;
244 marker.scale.z = 0.05;
245 marker.color = color;
276 : front_offset_(front_offset), front_radius_(front_radius), rear_offset_(rear_offset), rear_radius_(rear_radius) { }
290 void setParameters(
double front_offset,
double front_radius,
double rear_offset,
double rear_radius)
291 {front_offset_=front_offset; front_radius_=front_radius; rear_offset_=rear_offset; rear_radius_=rear_radius;}
304 return std::min(dist_front, dist_rear);
319 return std::min(dist_front, dist_rear);
331 virtual void visualizeRobot(
const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers,
const std_msgs::ColorRGBA& color)
const 336 markers.push_back(visualization_msgs::Marker());
337 visualization_msgs::Marker& marker1 = markers.back();
338 marker1.type = visualization_msgs::Marker::CYLINDER;
340 marker1.pose.position.x += front_offset_*dir.x();
341 marker1.pose.position.y += front_offset_*dir.y();
342 marker1.scale.x = marker1.scale.y = 2*front_radius_;
344 marker1.color = color;
349 markers.push_back(visualization_msgs::Marker());
350 visualization_msgs::Marker& marker2 = markers.back();
351 marker2.type = visualization_msgs::Marker::CYLINDER;
353 marker2.pose.position.x -= rear_offset_*dir.x();
354 marker2.pose.position.y -= rear_offset_*dir.y();
355 marker2.scale.x = marker2.scale.y = 2*rear_radius_;
357 marker2.color = color;
367 double min_longitudinal = std::min(rear_offset_ + rear_radius_, front_offset_ + front_radius_);
368 double min_lateral = std::min(rear_radius_, front_radius_);
369 return std::min(min_longitudinal, min_lateral);
398 setLine(line_start, line_end);
408 setLine(line_start, line_end);
422 line_start_.x() = line_start.x;
423 line_start_.y() = line_start.y;
424 line_end_.x() = line_end.x;
425 line_end_.y() = line_end.y;
446 Eigen::Vector2d line_start_world;
447 Eigen::Vector2d line_end_world;
448 transformToWorld(current_pose, line_start_world, line_end_world);
461 Eigen::Vector2d line_start_world;
462 Eigen::Vector2d line_end_world;
463 transformToWorld(current_pose, line_start_world, line_end_world);
476 virtual void visualizeRobot(
const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers,
const std_msgs::ColorRGBA& color)
const 478 markers.push_back(visualization_msgs::Marker());
479 visualization_msgs::Marker& marker = markers.back();
480 marker.type = visualization_msgs::Marker::LINE_STRIP;
484 geometry_msgs::Point line_start_world;
485 line_start_world.x = line_start_.x();
486 line_start_world.y = line_start_.y();
487 line_start_world.z = 0;
488 marker.points.push_back(line_start_world);
490 geometry_msgs::Point line_end_world;
491 line_end_world.x = line_end_.x();
492 line_end_world.y = line_end_.y();
493 line_end_world.z = 0;
494 marker.points.push_back(line_end_world);
496 marker.scale.x = 0.05;
497 marker.color = color;
519 double cos_th = std::cos(current_pose.
theta());
520 double sin_th = std::sin(current_pose.
theta());
521 line_start_world.x() = current_pose.
x() + cos_th * line_start_.x() - sin_th * line_start_.y();
522 line_start_world.y() = current_pose.
y() + sin_th * line_start_.x() + cos_th * line_start_.y();
523 line_end_world.x() = current_pose.
x() + cos_th * line_end_.x() - sin_th * line_end_.y();
524 line_end_world.y() = current_pose.
y() + sin_th * line_end_.x() + cos_th * line_end_.y();
531 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
573 transformToWorld(current_pose, polygon_world);
587 transformToWorld(current_pose, polygon_world);
600 virtual void visualizeRobot(
const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers,
const std_msgs::ColorRGBA& color)
const 602 if (vertices_.empty())
605 markers.push_back(visualization_msgs::Marker());
606 visualization_msgs::Marker& marker = markers.back();
607 marker.type = visualization_msgs::Marker::LINE_STRIP;
610 for (std::size_t i = 0; i < vertices_.size(); ++i)
612 geometry_msgs::Point
point;
613 point.x = vertices_[i].x();
614 point.y = vertices_[i].y();
616 marker.points.push_back(point);
619 geometry_msgs::Point
point;
620 point.x = vertices_.front().x();
621 point.y = vertices_.front().y();
623 marker.points.push_back(point);
625 marker.scale.x = 0.025;
626 marker.color = color;
636 double min_dist = std::numeric_limits<double>::max();
637 Eigen::Vector2d center(0.0, 0.0);
639 if (vertices_.size() <= 2)
642 for (
int i = 0; i < (int)vertices_.size() - 1; ++i)
645 double vertex_dist = vertices_[i].norm();
647 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
651 double vertex_dist = vertices_.back().norm();
653 return std::min(min_dist, std::min(vertex_dist, edge_dist));
665 double cos_th = std::cos(current_pose.
theta());
666 double sin_th = std::sin(current_pose.
theta());
667 for (std::size_t i=0; i<vertices_.size(); ++i)
669 polygon_world[i].x() = current_pose.
x() + cos_th * vertices_[i].x() - sin_th * vertices_[i].y();
670 polygon_world[i].y() = current_pose.
y() + sin_th * vertices_[i].x() + cos_th * vertices_[i].y();
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...
Eigen::Vector2d & position()
Access the 2D position part.
double & x()
Access the x-coordinate the pose.
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
Abbrev. for a container storing 2d points.
Eigen::Vector2d orientationUnitVec() const
Return the unit vector of the current orientation.
virtual double getMinimumDistance(const Eigen::Vector2d &position) const =0
Get the minimum euclidean distance to the obstacle (point as reference)
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.
void toPoseMsg(geometry_msgs::Pose &pose) const
Convert PoseSE2 to a geometry_msgs::Pose.
boost::shared_ptr< const BaseRobotFootprintModel > RobotFootprintModelConstPtr
Abbrev. for shared obstacle const pointers.
double & y()
Access the y-coordinate the pose.
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
double & theta()
Access the orientation part (yaw angle) of the pose.
boost::shared_ptr< BaseRobotFootprintModel > RobotFootprintModelPtr
Abbrev. for shared obstacle pointers.
Abstract class that defines the interface for modelling obstacles.