Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

costmap_cspace: move XML-polygon conversion into Polygon class #102

Merged
merged 1 commit into from
Jan 22, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
46 changes: 4 additions & 42 deletions costmap_cspace/include/costmap_3d_layer_footprint.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,15 +42,6 @@
#include <costmap_3d_layer_base.h>
#include <polygon.h>

namespace XmlRpc
{
bool isNumber(const XmlRpc::XmlRpcValue &value)
{
return value.getType() == XmlRpc::XmlRpcValue::TypeInt ||
value.getType() == XmlRpc::XmlRpcValue::TypeDouble;
}
} // namespace XmlRpc

namespace costmap_cspace
{
class Costmap3dLayerFootprint : public Costmap3dLayerBase
Expand All @@ -64,40 +55,11 @@ class Costmap3dLayerFootprint : public Costmap3dLayerBase
Polygon footprint_p_;

public:
bool setFootprint(const XmlRpc::XmlRpcValue footprint_xml_const)
bool setFootprint(const Polygon footprint)
{
XmlRpc::XmlRpcValue footprint_xml = footprint_xml_const;
if (footprint_xml.getType() != XmlRpc::XmlRpcValue::TypeArray || footprint_xml.size() < 3)
{
return false;
}

footprint_.polygon.points.clear();
footprint_.header.frame_id = "base_link";
footprint_radius_ = 0;
for (int i = 0; i < footprint_xml.size(); i++)
{
if (!XmlRpc::isNumber(footprint_xml[i][0]) ||
!XmlRpc::isNumber(footprint_xml[i][1]))
{
return false;
}

geometry_msgs::Point32 point;
Vec v;
v[0] = point.x = static_cast<double>(footprint_xml[i][0]);
v[1] = point.y = static_cast<double>(footprint_xml[i][1]);
point.z = 0;
footprint_.polygon.points.push_back(point);

footprint_p_.v.push_back(v);

const auto dist = hypotf(point.x, point.y);
if (dist > footprint_radius_)
footprint_radius_ = dist;
}
footprint_p_.v.push_back(footprint_p_.v.front());
footprint_.polygon.points.push_back(footprint_.polygon.points[0]);
footprint_p_ = footprint;
footprint_radius_ = footprint.radius();
footprint_ = footprint.toMsg();

return true;
}
Expand Down
66 changes: 66 additions & 0 deletions costmap_cspace/include/polygon.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,15 @@
#include <ros/ros.h>
#include <vector>

namespace XmlRpc
{
bool isNumber(const XmlRpc::XmlRpcValue &value)
{
return value.getType() == XmlRpc::XmlRpcValue::TypeInt ||
value.getType() == XmlRpc::XmlRpcValue::TypeDouble;
}
} // namespace XmlRpc

namespace costmap_cspace
{
class Vec
Expand Down Expand Up @@ -85,6 +94,63 @@ class Polygon
{
public:
std::vector<Vec> v;

Polygon()
{
}
explicit Polygon(const XmlRpc::XmlRpcValue footprint_xml_const)
{
XmlRpc::XmlRpcValue footprint_xml = footprint_xml_const;
if (footprint_xml.getType() != XmlRpc::XmlRpcValue::TypeArray || footprint_xml.size() < 3)
{
throw std::runtime_error("Invalid footprint xml.");
}

for (int i = 0; i < footprint_xml.size(); i++)
{
if (!XmlRpc::isNumber(footprint_xml[i][0]) ||
!XmlRpc::isNumber(footprint_xml[i][1]))
{
throw std::runtime_error("Invalid footprint xml.");
}

Vec p;
p[0] = static_cast<double>(footprint_xml[i][0]);
p[1] = static_cast<double>(footprint_xml[i][1]);

v.push_back(p);
}
v.push_back(v.front());
}
geometry_msgs::PolygonStamped toMsg() const
{
geometry_msgs::PolygonStamped msg;

msg.polygon.points.clear();
msg.header.frame_id = "base_link";
for (const auto &p : v)
{
geometry_msgs::Point32 point;
point.x = p[0];
point.y = p[1];
point.z = 0;
msg.polygon.points.push_back(point);
}
msg.polygon.points.push_back(msg.polygon.points[0]);

return msg;
}
float radius() const
{
float radius = 0;
for (const auto &p : v)
{
const auto dist = hypotf(p[0], p[1]);
if (dist > radius)
radius = dist;
}
return radius;
}
void move(const float &x, const float &y, const float &yaw)
{
float cos_v = cosf(yaw);
Expand Down
23 changes: 12 additions & 11 deletions costmap_cspace/src/costmap_3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,26 +157,27 @@ class Costmap3DOFNode
throw std::runtime_error("Footprint doesn't specified.");
}
nhp_.getParam("footprint", footprint_xml);
costmap_cspace::Polygon footprint;
try
{
footprint = costmap_cspace::Polygon(footprint_xml);
}
catch (const std::exception &e)
{
ROS_FATAL("Invalid footprint");
throw e;
}

costmaps_.resize(2);

costmap_cspace::Costmap3dLayerFootprint::Ptr costmap_base(new costmap_cspace::Costmap3dLayerFootprint);
costmap_base->setCSpaceConfig(ang_resolution, linear_expand, linear_spread, overlay_mode);
if (!costmap_base->setFootprint(footprint_xml))
{
ROS_FATAL("Invalid footprint");
throw std::runtime_error("Invalid footprint");
}
ROS_INFO("footprint radius: %0.3f", costmap_base->getFootprintRadius());
costmap_base->setFootprint(footprint);
costmaps_[0] = costmap_base;

costmap_cspace::Costmap3dLayerFootprint::Ptr costmap_overlay(new costmap_cspace::Costmap3dLayerFootprint);
costmap_overlay->setCSpaceConfig(ang_resolution, linear_expand, linear_spread, overlay_mode);
if (!costmap_overlay->setFootprint(footprint_xml))
{
ROS_FATAL("Invalid footprint");
throw std::runtime_error("Invalid footprint");
}
costmap_overlay->setFootprint(footprint);
costmaps_[1] = costmap_overlay;
costmaps_[0]->setChild(costmaps_[1]);

Expand Down
28 changes: 15 additions & 13 deletions costmap_cspace/test/src/test_costmap_3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,9 +74,9 @@ TEST(Costmap3dLayerFootprintTest, testCSpaceTemplate)

// Set example footprint
int footprint_offset = 0;
XmlRpc::XmlRpcValue footprint;
ASSERT_TRUE(footprint.fromXml(footprint_str, &footprint_offset));
ASSERT_TRUE(cm.setFootprint(footprint));
XmlRpc::XmlRpcValue footprint_xml;
ASSERT_TRUE(footprint_xml.fromXml(footprint_str, &footprint_offset));
ASSERT_TRUE(cm.setFootprint(costmap_cspace::Polygon(footprint_xml)));

// Check local footprint
const costmap_cspace::Polygon polygon = cm.getFootprint();
Expand Down Expand Up @@ -191,9 +191,9 @@ TEST(Costmap3dLayerFootprintTest, testCSpaceGenerate)

// Set example footprint
int footprint_offset = 0;
XmlRpc::XmlRpcValue footprint;
footprint.fromXml(footprint_str, &footprint_offset);
cm.setFootprint(footprint);
XmlRpc::XmlRpcValue footprint_xml;
footprint_xml.fromXml(footprint_str, &footprint_offset);
cm.setFootprint(costmap_cspace::Polygon(footprint_xml));

// Settings: 4 angular grids, no expand/spread
cm.setCSpaceConfig(4, 0.0, 0.0, costmap_cspace::Costmap3dLayerFootprint::map_overlay_mode::MAX);
Expand Down Expand Up @@ -301,9 +301,9 @@ TEST(Costmap3dLayerFootprintTest, testCSpaceExpandSpread)

// Set example footprint
int footprint_offset = 0;
XmlRpc::XmlRpcValue footprint;
footprint.fromXml(footprint_str, &footprint_offset);
cm.setFootprint(footprint);
XmlRpc::XmlRpcValue footprint_xml;
footprint_xml.fromXml(footprint_str, &footprint_offset);
cm.setFootprint(costmap_cspace::Polygon(footprint_xml));

// Settings: 4 angular grids, expand 1.0, spread 2.0
const float expand = 1.0;
Expand Down Expand Up @@ -372,8 +372,9 @@ TEST(Costmap3dLayerFootprintTest, testCSpaceOverwrite)

// Set example footprint
int footprint_offset = 0;
XmlRpc::XmlRpcValue footprint;
footprint.fromXml(footprint_str, &footprint_offset);
XmlRpc::XmlRpcValue footprint_xml;
footprint_xml.fromXml(footprint_str, &footprint_offset);
costmap_cspace::Polygon footprint(footprint_xml);
cm->setFootprint(footprint);
cm_over->setFootprint(footprint);
cm_ref.setFootprint(footprint);
Expand Down Expand Up @@ -514,8 +515,9 @@ TEST(Costmap3dLayerFootprintTest, testCSpaceOverlayMove)

// Set example footprint
int footprint_offset = 0;
XmlRpc::XmlRpcValue footprint;
footprint.fromXml(footprint_str, &footprint_offset);
XmlRpc::XmlRpcValue footprint_xml;
footprint_xml.fromXml(footprint_str, &footprint_offset);
costmap_cspace::Polygon footprint(footprint_xml);
cm->setFootprint(footprint);
cm_over->setFootprint(footprint);

Expand Down