hiep sua ten file
This commit is contained in:
@@ -23,14 +23,14 @@ namespace costmap_2d
|
||||
{
|
||||
if (directional_areas_.empty())
|
||||
throw "Has no map data";
|
||||
nav_msgs::Path path;
|
||||
robot_nav_msgs::Path path;
|
||||
path.header.stamp = robot::Time::now();
|
||||
path.header.frame_id = map_frame_;
|
||||
path.poses = plan;
|
||||
return this->laneFilter(directional_areas_, path);
|
||||
}
|
||||
|
||||
void DirectionalLayer::incomingMap(const nav_msgs::OccupancyGrid& new_map)
|
||||
void DirectionalLayer::incomingMap(const robot_nav_msgs::OccupancyGrid& new_map)
|
||||
{
|
||||
if(!map_shutdown_)
|
||||
{
|
||||
@@ -110,7 +110,7 @@ namespace costmap_2d
|
||||
}
|
||||
}
|
||||
|
||||
bool DirectionalLayer::laneFilter(std::vector<std::array<uint16_t, 2>> new_map, const nav_msgs::Path path)
|
||||
bool DirectionalLayer::laneFilter(std::vector<std::array<uint16_t, 2>> new_map, const robot_nav_msgs::Path path)
|
||||
{
|
||||
boost::unique_lock<mutex_t> lock(*layered_costmap_->getCostmap()->getMutex());
|
||||
if (new_map.empty())
|
||||
@@ -159,7 +159,7 @@ namespace costmap_2d
|
||||
if (!Yaw_list.empty())
|
||||
{
|
||||
laneFilter(X_List, Y_List, Yaw_list);
|
||||
nav_msgs::OccupancyGrid lanes;
|
||||
robot_nav_msgs::OccupancyGrid lanes;
|
||||
convertToMap(costmap_, lanes, 0.65, 0.196);
|
||||
|
||||
//////////////////////////////////
|
||||
@@ -177,7 +177,7 @@ namespace costmap_2d
|
||||
|
||||
}
|
||||
|
||||
void DirectionalLayer::convertToMap(unsigned char *costmap, nav_msgs::OccupancyGrid &dir_map, double occ_th, double free_th)
|
||||
void DirectionalLayer::convertToMap(unsigned char *costmap, robot_nav_msgs::OccupancyGrid &dir_map, double occ_th, double free_th)
|
||||
{
|
||||
dir_map.header = new_map_.header;
|
||||
dir_map.header.stamp = robot::Time::now();
|
||||
|
||||
Reference in New Issue
Block a user