30 #ifndef COSTMAP_CSPACE_POLYGON_H 31 #define COSTMAP_CSPACE_POLYGON_H 67 return (*
this)[0] * a[1] - (*this)[1] * a[0];
71 return (*
this)[0] * a[0] + (*this)[1] * a[1];
75 return std::hypot((*
this)[0] - a[0], (*
this)[1] - a[1]);
79 return (b - a).cross((*
this) - a) / b.
dist(a);
83 if ((b - a).
dot((*
this) - a) <= 0)
85 if ((a - b).
dot((*
this) - b) <= 0)
103 throw std::runtime_error(
"Invalid footprint xml.");
106 for (
int i = 0; i < footprint_xml.
size(); i++)
111 p[0] =
static_cast<double>(footprint_xml[i][0]);
112 p[1] =
static_cast<double>(footprint_xml[i][1]);
116 throw std::runtime_error((
"Invalid footprint xml." + e.
getMessage()).c_str());
121 v.push_back(v.front());
123 geometry_msgs::PolygonStamped
toMsg()
const 125 geometry_msgs::PolygonStamped msg;
127 msg.polygon.points.clear();
128 msg.header.frame_id =
"base_link";
129 for (
const auto& p : v)
131 geometry_msgs::Point32 point;
135 msg.polygon.points.push_back(point);
137 msg.polygon.points.push_back(msg.polygon.points[0]);
144 for (
const auto& p : v)
146 const auto dist = std::hypot(p[0], p[1]);
152 void move(
const float& x,
const float& y,
const float& yaw)
154 float cos_v = cosf(yaw);
155 float sin_v = sinf(yaw);
159 p[0] = cos_v * tmp[0] - sin_v * tmp[1] + x;
160 p[1] = sin_v * tmp[0] + cos_v * tmp[1] + y;
166 for (
size_t i = 0; i < v.size() - 1; i++)
170 if ((v1[1] <= a[1] && a[1] < v2[1]) ||
171 (v2[1] <= a[1] && a[1] < v1[1]))
174 lx = v1[0] + (v2[0] - v1[0]) * (a[1] - v1[1]) / (v2[1] - v1[1]);
179 return ((cn & 1) == 1);
183 float dist = std::numeric_limits<float>::max();
184 for (
size_t i = 0; i < v.size() - 1; i++)
197 #endif // COSTMAP_CSPACE_POLYGON_H Polygon(const XmlRpc::XmlRpcValue footprint_xml_const)
float dist_linestrip(const Vec &a, const Vec &b) const
const std::string & getMessage() const
float dot(const Vec &a) const
float cross(const Vec &a) const
void move(const float &x, const float &y, const float &yaw)
geometry_msgs::PolygonStamped toMsg() const
Type const & getType() const
const float & operator[](const int &i) const
bool inside(const Vec &a) const
float & operator[](const int &i)
float dist(const Vec &a) const
float dist(const Vec &a) const
float dist_line(const Vec &a, const Vec &b) const
Vec operator-(const Vec &a) const