diff --git a/include/costmap_2d/costmap_2d_robot.h b/include/costmap_2d/costmap_2d_robot.h index 6b2477e..da158b6 100755 --- a/include/costmap_2d/costmap_2d_robot.h +++ b/include/costmap_2d/costmap_2d_robot.h @@ -253,7 +253,7 @@ private: void readFootprintFromConfig(const std::vector &new_footprint, const std::vector &old_footprint, const double &robot_radius); - std::vector> creators_; + std::vector> creators_; void checkMovement(); void mapUpdateLoop(double frequency); bool map_update_thread_shutdown_; diff --git a/include/costmap_2d/layer.h b/include/costmap_2d/layer.h index 0c4313f..4754d52 100755 --- a/include/costmap_2d/layer.h +++ b/include/costmap_2d/layer.h @@ -163,7 +163,7 @@ private: std::vector footprint_spec_; }; -using PluginLayerPtr = std::shared_ptr; +using PluginLayerPtr = boost::shared_ptr; } // namespace costmap_2d diff --git a/include/costmap_2d/layered_costmap.h b/include/costmap_2d/layered_costmap.h index 59c49b9..72a8bdd 100755 --- a/include/costmap_2d/layered_costmap.h +++ b/include/costmap_2d/layered_costmap.h @@ -104,12 +104,12 @@ public: return costmap_.getDefaultValue() == costmap_2d::NO_INFORMATION; } - std::vector >* getPlugins() + std::vector >* getPlugins() { return &plugins_; } - void addPlugin(std::shared_ptr plugin) + void addPlugin(boost::shared_ptr plugin) { plugins_.push_back(plugin); } @@ -164,7 +164,7 @@ private: double minx_, miny_, maxx_, maxy_; unsigned int bx0_, bxn_, by0_, byn_; - std::vector > plugins_; + std::vector > plugins_; bool initialized_; bool size_locked_; diff --git a/plugins/critical_layer.cpp b/plugins/critical_layer.cpp index aacfddc..5995ae7 100644 --- a/plugins/critical_layer.cpp +++ b/plugins/critical_layer.cpp @@ -36,8 +36,8 @@ void CriticalLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, i } // Export factory function -static std::shared_ptr create_critical_plugin() { - return std::make_shared(); +static boost::shared_ptr create_critical_plugin() { + return boost::make_shared(); } // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) diff --git a/plugins/directional_layer.cpp b/plugins/directional_layer.cpp index 70a0a82..8fc0dce 100644 --- a/plugins/directional_layer.cpp +++ b/plugins/directional_layer.cpp @@ -428,8 +428,8 @@ namespace costmap_2d } // Export factory function - static std::shared_ptr create_directional_plugin() { - return std::make_shared(); + static boost::shared_ptr create_directional_plugin() { + return boost::make_shared(); } // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) diff --git a/plugins/inflation_layer.cpp b/plugins/inflation_layer.cpp index 28dedd7..d42017e 100755 --- a/plugins/inflation_layer.cpp +++ b/plugins/inflation_layer.cpp @@ -397,8 +397,8 @@ void InflationLayer::handleImpl(const void* data, // Export factory function -static std::shared_ptr create_inflation_plugin() { - return std::make_shared(); +static boost::shared_ptr create_inflation_plugin() { + return boost::make_shared(); } // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) diff --git a/plugins/obstacle_layer.cpp b/plugins/obstacle_layer.cpp index 6b95bf6..1b53d48 100755 --- a/plugins/obstacle_layer.cpp +++ b/plugins/obstacle_layer.cpp @@ -555,8 +555,8 @@ void ObstacleLayer::reset() } // Export factory function -static std::shared_ptr create_obstacle_plugin() { - return std::make_shared(); +static boost::shared_ptr create_obstacle_plugin() { + return boost::make_shared(); } // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) diff --git a/plugins/preferred_layer.cpp b/plugins/preferred_layer.cpp index 3592c09..555b36d 100644 --- a/plugins/preferred_layer.cpp +++ b/plugins/preferred_layer.cpp @@ -25,8 +25,8 @@ unsigned char PreferredLayer::interpretValue(unsigned char value) } // Export factory function -static std::shared_ptr create_preferred_plugin() { - return std::make_shared(); +static boost::shared_ptr create_preferred_plugin() { + return boost::make_shared(); } // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) diff --git a/plugins/static_layer.cpp b/plugins/static_layer.cpp index 02e61f3..d697a06 100755 --- a/plugins/static_layer.cpp +++ b/plugins/static_layer.cpp @@ -361,8 +361,8 @@ void StaticLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int } // Export factory function -static std::shared_ptr create_static_plugin() { - return std::make_shared(); +static boost::shared_ptr create_static_plugin() { + return boost::make_shared(); } // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) diff --git a/plugins/unpreferred_layer.cpp b/plugins/unpreferred_layer.cpp index 327f359..0ba8276 100644 --- a/plugins/unpreferred_layer.cpp +++ b/plugins/unpreferred_layer.cpp @@ -23,8 +23,8 @@ unsigned char UnPreferredLayer::interpretValue(unsigned char value) } // Export factory function -static std::shared_ptr create_unpreferred_plugin() { - return std::make_shared(); +static boost::shared_ptr create_unpreferred_plugin() { + return boost::make_shared(); } // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) diff --git a/plugins/voxel_layer.cpp b/plugins/voxel_layer.cpp index d2f1d9f..3a5fbd6 100755 --- a/plugins/voxel_layer.cpp +++ b/plugins/voxel_layer.cpp @@ -450,8 +450,8 @@ void VoxelLayer::updateOrigin(double new_origin_x, double new_origin_y) } // Export factory function -static std::shared_ptr create_voxel_plugin() { - return std::make_shared(); +static boost::shared_ptr create_voxel_plugin() { + return boost::make_shared(); } // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) diff --git a/src/layered_costmap.cpp b/src/layered_costmap.cpp index 6e26057..6c590cc 100755 --- a/src/layered_costmap.cpp +++ b/src/layered_costmap.cpp @@ -85,7 +85,7 @@ namespace costmap_2d boost::unique_lock lock(*(costmap_.getMutex())); size_locked_ = size_locked; costmap_.resizeMap(size_x, size_y, resolution, origin_x, origin_y); - for (vector>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); + for (vector>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); ++plugin) { (*plugin)->matchSize(); @@ -112,7 +112,7 @@ namespace costmap_2d minx_ = miny_ = 1e30; maxx_ = maxy_ = -1e30; - for (vector>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); + for (vector>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); ++plugin) { if (!(*plugin)->isEnabled()) @@ -148,7 +148,7 @@ namespace costmap_2d costmap_.resetMap(x0, y0, xn, yn); - for (vector>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); + for (vector>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); ++plugin) { if ((*plugin)->isEnabled()) @@ -166,7 +166,7 @@ namespace costmap_2d bool LayeredCostmap::isCurrent() { current_ = true; - for (vector>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); + for (vector>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); ++plugin) { if ((*plugin)->isEnabled()) @@ -180,7 +180,7 @@ namespace costmap_2d footprint_ = footprint_spec; costmap_2d::calculateMinAndMaxDistances(footprint_spec, inscribed_radius_, circumscribed_radius_); - for (vector>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); + for (vector>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); ++plugin) { (*plugin)->onFootprintChanged(); diff --git a/test/static_layer_test.cpp b/test/static_layer_test.cpp index 65d6e5b..a27156f 100644 --- a/test/static_layer_test.cpp +++ b/test/static_layer_test.cpp @@ -2,6 +2,7 @@ #include #include #include +#include namespace costmap_2d {