40 #ifndef ROBOT_FOOTPRINT_MODEL_H
41 #define ROBOT_FOOTPRINT_MODEL_H
45 #include <visualization_msgs/Marker.h>
58 class BaseRobotFootprintModel
83 virtual double calculateDistance(
const PoseSE2& current_pose,
const Obstacle* obstacle)
const = 0;
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
134 class PointRobotFootprint :
public BaseRobotFootprintModel
160 virtual double calculateDistance(
const PoseSE2& current_pose,
const Obstacle* obstacle)
const
162 return obstacle->getMinimumDistance(current_pose.position());
174 return obstacle->getMinimumSpatioTemporalDistance(current_pose.position(), t);
192 virtual void visualizeRobot(
const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers,
const std_msgs::ColorRGBA& color)
const
195 markers.push_back(visualization_msgs::Marker());
196 visualization_msgs::Marker& marker = markers.back();
197 marker.type = visualization_msgs::Marker::POINTS;
198 current_pose.toPoseMsg(marker.pose);
199 marker.points.push_back(geometry_msgs::Point());
200 marker.scale.x = 0.025;
201 marker.color = color;
209 markers.push_back(visualization_msgs::Marker());
210 visualization_msgs::Marker& marker2 = markers.back();
211 marker2.type = visualization_msgs::Marker::LINE_STRIP;
212 marker2.scale.x = 0.025;
213 marker2.color = color;
214 current_pose.toPoseMsg(marker2.pose);
218 for (
double theta = 0; theta <= 2 * M_PI; theta += M_PI / n)
220 geometry_msgs::Point pt;
221 pt.x = r * cos(theta);
222 pt.y = r * sin(theta);
223 marker2.points.push_back(pt);
263 virtual double calculateDistance(
const PoseSE2& current_pose,
const Obstacle* obstacle)
const
265 return obstacle->getMinimumDistance(current_pose.position()) -
radius_;
289 virtual void visualizeRobot(
const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers,
const std_msgs::ColorRGBA& color)
const
292 visualization_msgs::Marker& marker = markers.back();
293 marker.type = visualization_msgs::Marker::CYLINDER;
294 current_pose.toPoseMsg(marker.pose);
295 marker.scale.x = marker.scale.y = 2*
radius_;
296 marker.scale.z = 0.05;
297 marker.color = color;
342 void setParameters(
double front_offset,
double front_radius,
double rear_offset,
double rear_radius)
356 return std::min(dist_front, dist_rear);
371 return std::min(dist_front, dist_rear);
383 virtual void visualizeRobot(
const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers,
const std_msgs::ColorRGBA& color)
const
388 markers.push_back(visualization_msgs::Marker());
389 visualization_msgs::Marker& marker1 = markers.back();
390 marker1.type = visualization_msgs::Marker::CYLINDER;
396 marker1.color = color;
401 markers.push_back(visualization_msgs::Marker());
402 visualization_msgs::Marker& marker2 = markers.back();
403 marker2.type = visualization_msgs::Marker::CYLINDER;
409 marker2.color = color;
421 return std::min(min_longitudinal, min_lateral);
439 class LineRobotFootprint :
public BaseRobotFootprintModel
498 Eigen::Vector2d line_start_world;
499 Eigen::Vector2d line_end_world;
513 Eigen::Vector2d line_start_world;
514 Eigen::Vector2d line_end_world;
528 virtual void visualizeRobot(
const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers,
const std_msgs::ColorRGBA& color)
const
530 markers.push_back(visualization_msgs::Marker());
531 visualization_msgs::Marker& marker = markers.back();
532 marker.type = visualization_msgs::Marker::LINE_STRIP;
533 current_pose.toPoseMsg(marker.pose);
536 geometry_msgs::Point line_start_world;
539 line_start_world.z = 0;
540 marker.points.push_back(line_start_world);
542 geometry_msgs::Point line_end_world;
545 line_end_world.z = 0;
546 marker.points.push_back(line_end_world);
548 marker.scale.x = 0.025;
549 marker.color = color;
557 markers.push_back(visualization_msgs::Marker());
558 visualization_msgs::Marker& marker2 = markers.back();
559 marker2.type = visualization_msgs::Marker::LINE_STRIP;
560 marker2.scale.x = 0.025;
561 marker2.color = color;
562 current_pose.toPoseMsg(marker2.pose);
569 for (
double theta = M_PI_2 + ori; theta <= 3 * M_PI_2 + ori; theta += M_PI / n)
571 geometry_msgs::Point pt;
574 marker2.points.push_back(pt);
578 for (
double theta = -M_PI_2 + ori; theta <= M_PI_2 + ori; theta += M_PI / n)
580 geometry_msgs::Point pt;
583 marker2.points.push_back(pt);
587 geometry_msgs::Point pt;
590 marker2.points.push_back(pt);
610 void transformToWorld(
const PoseSE2& current_pose, Eigen::Vector2d& line_start_world, Eigen::Vector2d& line_end_world)
const
612 double cos_th = std::cos(current_pose.theta());
613 double sin_th = std::sin(current_pose.theta());
616 line_end_world.x() = current_pose.x() + cos_th *
line_end_.x() - sin_th *
line_end_.y();
617 line_end_world.y() = current_pose.y() + sin_th *
line_end_.x() + cos_th *
line_end_.y();
625 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
635 class PolygonRobotFootprint :
public BaseRobotFootprintModel
694 virtual void visualizeRobot(
const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers,
const std_msgs::ColorRGBA& color)
const
699 markers.push_back(visualization_msgs::Marker());
700 visualization_msgs::Marker& marker = markers.back();
701 marker.type = visualization_msgs::Marker::LINE_STRIP;
704 for (std::size_t i = 0; i <
vertices_.size(); ++i)
706 geometry_msgs::Point
point;
710 marker.points.push_back(
point);
713 geometry_msgs::Point
point;
717 marker.points.push_back(
point);
719 marker.scale.x = 0.025;
720 marker.color = color;
730 double min_dist = std::numeric_limits<double>::max();
731 Eigen::Vector2d center(0.0, 0.0);
736 for (
int i = 0; i < (int)
vertices_.size() - 1; ++i)
739 double vertex_dist =
vertices_[i].norm();
741 min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
745 double vertex_dist =
vertices_.back().norm();
747 return std::min(min_dist, std::min(vertex_dist, edge_dist));
759 double cos_th = std::cos(current_pose.theta());
760 double sin_th = std::sin(current_pose.theta());
761 for (std::size_t i=0; i<
vertices_.size(); ++i)
763 polygon_world[i].x() = current_pose.x() + cos_th *
vertices_[i].x() - sin_th *
vertices_[i].y();