-
Notifications
You must be signed in to change notification settings - Fork 91
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: add stacked costmap class #104
Merged
Merged
Changes from 2 commits
Commits
Show all changes
4 commits
Select commit
Hold shift + click to select a range
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -38,6 +38,7 @@ | |
#include <costmap_cspace/CSpace3DUpdate.h> | ||
|
||
#include <cspace3_cache.h> | ||
#include <polygon.h> | ||
|
||
namespace costmap_cspace | ||
{ | ||
|
@@ -76,6 +77,75 @@ class Costmap3dLayerBase | |
OVERWRITE, | ||
MAX | ||
}; | ||
class UpdatedRegion | ||
{ | ||
public: | ||
int x_, y_, yaw_; | ||
int width_, height_, angle_; | ||
ros::Time stamp_; | ||
|
||
UpdatedRegion() | ||
: x_(0) | ||
, y_(0) | ||
, yaw_(0) | ||
, width_(0) | ||
, height_(0) | ||
, angle_(0) | ||
, stamp_(0) | ||
{ | ||
} | ||
UpdatedRegion( | ||
const int &x, const int &y, const int &yaw, | ||
const int &width, const int &height, const int &angle, | ||
const ros::Time &stamp) | ||
: x_(x) | ||
, y_(y) | ||
, yaw_(yaw) | ||
, width_(width) | ||
, height_(height) | ||
, angle_(angle) | ||
, stamp_(stamp) | ||
{ | ||
} | ||
void merge(const UpdatedRegion ®ion) | ||
{ | ||
if (region.width_ == 0 || region.height_ == 0 || region.angle_ == 0) | ||
return; | ||
if (region.stamp_ > stamp_) | ||
stamp_ = region.stamp_; | ||
|
||
if (width_ == 0 || height_ == 0 || angle_ == 0) | ||
{ | ||
*this = region; | ||
return; | ||
} | ||
int x2 = x_ + width_; | ||
int y2 = y_ + height_; | ||
int yaw2 = yaw_ + angle_; | ||
|
||
const int mx2 = region.x_ + region.width_; | ||
const int my2 = region.y_ + region.height_; | ||
const int myaw2 = region.yaw_ + region.angle_; | ||
|
||
if (region.x_ < x_) | ||
x_ = region.x_; | ||
if (region.y_ < y_) | ||
y_ = region.y_; | ||
if (region.yaw_ < yaw_) | ||
yaw_ = region.yaw_; | ||
|
||
if (x2 < mx2) | ||
x2 = mx2; | ||
if (y2 < my2) | ||
y2 = my2; | ||
if (yaw2 < myaw2) | ||
yaw2 = myaw2; | ||
|
||
width_ = x2 - x_; | ||
height_ = y2 - y_; | ||
angle_ = yaw2 - yaw_; | ||
} | ||
}; | ||
|
||
using Ptr = std::shared_ptr<Costmap3dLayerBase>; | ||
|
||
|
@@ -91,9 +161,9 @@ class Costmap3dLayerBase | |
|
||
CSpace3DMsg::Ptr map_; | ||
CSpace3DMsg::Ptr map_overlay_; | ||
nav_msgs::OccupancyGrid map_base_; | ||
|
||
Costmap3dLayerBase::Ptr child_; | ||
UpdatedRegion region_; | ||
|
||
public: | ||
Costmap3dLayerBase() | ||
|
@@ -102,21 +172,28 @@ class Costmap3dLayerBase | |
, linear_spread_(0.0) | ||
, overlay_mode_(map_overlay_mode::MAX) | ||
, root_(true) | ||
, range_max_(0) | ||
, map_(new CSpace3DMsg) | ||
, map_overlay_(new CSpace3DMsg) | ||
{ | ||
} | ||
void setCSpaceConfig( | ||
const int ang_resolution, | ||
const float linear_expand, | ||
const float linear_spread, | ||
const map_overlay_mode overlay_mode) | ||
const float linear_spread) | ||
{ | ||
ang_grid_ = ang_resolution; | ||
linear_expand_ = linear_expand; | ||
linear_spread_ = linear_spread; | ||
} | ||
void setOverlayMode( | ||
const map_overlay_mode overlay_mode) | ||
{ | ||
overlay_mode_ = overlay_mode; | ||
} | ||
void setFootprint(const Polygon footprint) | ||
{ | ||
} | ||
void setChild(Costmap3dLayerBase::Ptr child) | ||
{ | ||
child_ = child; | ||
|
@@ -127,53 +204,56 @@ class Costmap3dLayerBase | |
void setBaseMap(const nav_msgs::OccupancyGrid &base_map) | ||
{ | ||
ROS_ASSERT(root_); | ||
ROS_ASSERT(ang_grid_ > 0); | ||
ROS_ASSERT(base_map.data.size() >= base_map.info.width * base_map.info.height); | ||
map_base_ = base_map; | ||
|
||
map_->header = map_base_.header; | ||
map_->info.width = map_base_.info.width; | ||
map_->info.height = map_base_.info.height; | ||
const size_t xy_size = base_map.info.width * base_map.info.height; | ||
map_->header = base_map.header; | ||
map_->info.width = base_map.info.width; | ||
map_->info.height = base_map.info.height; | ||
map_->info.angle = ang_grid_; | ||
map_->info.linear_resolution = map_base_.info.resolution; | ||
map_->info.linear_resolution = base_map.info.resolution; | ||
map_->info.angular_resolution = 2.0 * M_PI / ang_grid_; | ||
map_->info.origin = map_base_.info.origin; | ||
map_->data.resize(map_base_.data.size() * map_->info.angle); | ||
map_->info.origin = base_map.info.origin; | ||
map_->data.resize(xy_size * map_->info.angle); | ||
|
||
generateCSpaceTemplate(map_->info); | ||
|
||
for (size_t yaw = 0; yaw < map_->info.angle; yaw++) | ||
{ | ||
for (unsigned int i = 0; i < map_base_.data.size(); i++) | ||
for (unsigned int i = 0; i < xy_size; i++) | ||
{ | ||
map_->data[i + yaw * map_base_.data.size()] = 0; | ||
map_->data[i + yaw * xy_size] = 0; | ||
} | ||
} | ||
gemerateCSpace(map_, map_base_); | ||
gemerateCSpace(map_, base_map); | ||
for (size_t yaw = 0; yaw < map_->info.angle; yaw++) | ||
{ | ||
for (unsigned int i = 0; i < map_base_.data.size(); i++) | ||
for (unsigned int i = 0; i < xy_size; i++) | ||
{ | ||
if (map_base_.data[i] < 0) | ||
if (base_map.data[i] < 0) | ||
{ | ||
map_->data[i + yaw * map_base_.data.size()] = -1; | ||
map_->data[i + yaw * xy_size] = -1; | ||
} | ||
} | ||
} | ||
*map_overlay_ = *map_; | ||
if (child_) | ||
child_->setBaseMapChain(); | ||
} | ||
CSpace3DUpdate processMapOverlay(const nav_msgs::OccupancyGrid &msg) | ||
void processMapOverlay(const nav_msgs::OccupancyGrid &msg) | ||
{ | ||
ROS_ASSERT(!root_); | ||
ROS_ASSERT(ang_grid_ > 0); | ||
const int ox = lroundf((msg.info.origin.position.x - map_->info.origin.position.x) / map_->info.linear_resolution); | ||
const int oy = lroundf((msg.info.origin.position.y - map_->info.origin.position.y) / map_->info.linear_resolution); | ||
*map_overlay_ = *map_; | ||
gemerateCSpace(map_overlay_, msg, true); | ||
|
||
const int w = lroundf(msg.info.width * msg.info.resolution / map_->info.linear_resolution); | ||
const int h = lroundf(msg.info.height * msg.info.resolution / map_->info.linear_resolution); | ||
return generateUpdateMsg(map_overlay_, ox, oy, 0, w, h, map_->info.angle, msg.header.stamp); | ||
|
||
updateChainEntry(UpdatedRegion(ox, oy, 0, w, h, map_->info.angle, msg.header.stamp)); | ||
} | ||
CSpace3DMsg::Ptr getMap() | ||
{ | ||
|
@@ -201,6 +281,25 @@ class Costmap3dLayerBase | |
} | ||
|
||
protected: | ||
virtual bool updateChain() = 0; | ||
bool updateChainEntry(const UpdatedRegion ®ion) | ||
{ | ||
region_.merge(region); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. move impl of There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. only if non-empty region is stored |
||
if (updateChain()) | ||
{ | ||
region_ = UpdatedRegion(); | ||
return true; | ||
} | ||
|
||
if (child_) | ||
{ | ||
const bool clear = child_->updateChainEntry(region_); | ||
if (clear) | ||
region_ = UpdatedRegion(); | ||
return clear; | ||
} | ||
return false; | ||
} | ||
void setBaseMapChain() | ||
{ | ||
generateCSpaceTemplate(map_->info); | ||
|
@@ -210,6 +309,7 @@ class Costmap3dLayerBase | |
} | ||
void gemerateCSpace(CSpace3DMsg::Ptr map, const nav_msgs::OccupancyGrid &msg, bool overlay = false) | ||
{ | ||
ROS_ASSERT(ang_grid_ > 0); | ||
const int ox = lroundf((msg.info.origin.position.x - map->info.origin.position.x) / map->info.linear_resolution); | ||
const int oy = lroundf((msg.info.origin.position.y - map->info.origin.position.y) / map->info.linear_resolution); | ||
// Clear travelable area in OVERWRITE mode | ||
|
@@ -282,64 +382,6 @@ class Costmap3dLayerBase | |
} | ||
} | ||
} | ||
CSpace3DUpdate generateUpdateMsg( | ||
CSpace3DMsg::Ptr map, const int &x, const int &y, const int &yaw, | ||
const int &width, const int &height, const int &angle, | ||
const ros::Time &stamp) | ||
{ | ||
CSpace3DUpdate update; | ||
update.header = map->header; | ||
map->header.stamp = stamp; | ||
int update_x = x - range_max_; | ||
int update_y = y - range_max_; | ||
int update_width = width + range_max_ * 2; | ||
int update_height = height + range_max_ * 2; | ||
if (update_x < 0) | ||
{ | ||
update_width += update_x; | ||
update_x = 0; | ||
} | ||
if (update_y < 0) | ||
{ | ||
update_height += update_y; | ||
update_y = 0; | ||
} | ||
if (update_x + update_width > static_cast<int>(map->info.width)) | ||
{ | ||
update_width = map->info.width - update_x; | ||
} | ||
if (update_y + update_height > static_cast<int>(map->info.height)) | ||
{ | ||
update_height = map->info.height - update_y; | ||
} | ||
update.x = update_x; | ||
update.y = update_y; | ||
update.width = update_width; | ||
update.height = update_height; | ||
update.yaw = yaw; | ||
update.angle = angle; | ||
update.data.resize(update.width * update.height * update.angle); | ||
|
||
for (int i = 0; i < static_cast<int>(update.width); i++) | ||
{ | ||
for (int j = 0; j < static_cast<int>(update.height); j++) | ||
{ | ||
for (int k = 0; k < static_cast<int>(update.angle); k++) | ||
{ | ||
const int x2 = update.x + i; | ||
const int y2 = update.y + j; | ||
const int yaw2 = yaw + k; | ||
|
||
const auto &m = map->getCost(x2, y2, yaw2); | ||
const size_t addr = (k * update.height + j) * update.width + i; | ||
ROS_ASSERT(addr < update.data.size()); | ||
auto &up = update.data[addr]; | ||
up = m; | ||
} | ||
} | ||
} | ||
return update; | ||
} | ||
}; | ||
} // namespace costmap_cspace | ||
|
||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
store msg and region, then trigger
updateChainEntry