replace std::shared_ptr to boost::shared_ptr

This commit is contained in:
duongtd 2025-12-04 14:32:22 +07:00
parent f37bccd02f
commit af43332b28
13 changed files with 27 additions and 26 deletions

View File

@ -253,7 +253,7 @@ private:
void readFootprintFromConfig(const std::vector<geometry_msgs::Point> &new_footprint, void readFootprintFromConfig(const std::vector<geometry_msgs::Point> &new_footprint,
const std::vector<geometry_msgs::Point> &old_footprint, const std::vector<geometry_msgs::Point> &old_footprint,
const double &robot_radius); const double &robot_radius);
std::vector<std::function<PluginLayerPtr()>> creators_; std::vector<boost::function<PluginLayerPtr()>> creators_;
void checkMovement(); void checkMovement();
void mapUpdateLoop(double frequency); void mapUpdateLoop(double frequency);
bool map_update_thread_shutdown_; bool map_update_thread_shutdown_;

View File

@ -163,7 +163,7 @@ private:
std::vector<geometry_msgs::Point> footprint_spec_; std::vector<geometry_msgs::Point> footprint_spec_;
}; };
using PluginLayerPtr = std::shared_ptr<Layer>; using PluginLayerPtr = boost::shared_ptr<Layer>;
} // namespace costmap_2d } // namespace costmap_2d

View File

@ -104,12 +104,12 @@ public:
return costmap_.getDefaultValue() == costmap_2d::NO_INFORMATION; return costmap_.getDefaultValue() == costmap_2d::NO_INFORMATION;
} }
std::vector<std::shared_ptr<Layer> >* getPlugins() std::vector<boost::shared_ptr<Layer> >* getPlugins()
{ {
return &plugins_; return &plugins_;
} }
void addPlugin(std::shared_ptr<Layer> plugin) void addPlugin(boost::shared_ptr<Layer> plugin)
{ {
plugins_.push_back(plugin); plugins_.push_back(plugin);
} }
@ -164,7 +164,7 @@ private:
double minx_, miny_, maxx_, maxy_; double minx_, miny_, maxx_, maxy_;
unsigned int bx0_, bxn_, by0_, byn_; unsigned int bx0_, bxn_, by0_, byn_;
std::vector<std::shared_ptr<Layer> > plugins_; std::vector<boost::shared_ptr<Layer> > plugins_;
bool initialized_; bool initialized_;
bool size_locked_; bool size_locked_;

View File

@ -36,8 +36,8 @@ void CriticalLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, i
} }
// Export factory function // Export factory function
static std::shared_ptr<Layer> create_critical_plugin() { static boost::shared_ptr<Layer> create_critical_plugin() {
return std::make_shared<CriticalLayer>(); return boost::make_shared<CriticalLayer>();
} }
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)

View File

@ -428,8 +428,8 @@ namespace costmap_2d
} }
// Export factory function // Export factory function
static std::shared_ptr<Layer> create_directional_plugin() { static boost::shared_ptr<Layer> create_directional_plugin() {
return std::make_shared<DirectionalLayer>(); return boost::make_shared<DirectionalLayer>();
} }
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)

View File

@ -397,8 +397,8 @@ void InflationLayer::handleImpl(const void* data,
// Export factory function // Export factory function
static std::shared_ptr<Layer> create_inflation_plugin() { static boost::shared_ptr<Layer> create_inflation_plugin() {
return std::make_shared<InflationLayer>(); return boost::make_shared<InflationLayer>();
} }
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)

View File

@ -555,8 +555,8 @@ void ObstacleLayer::reset()
} }
// Export factory function // Export factory function
static std::shared_ptr<Layer> create_obstacle_plugin() { static boost::shared_ptr<Layer> create_obstacle_plugin() {
return std::make_shared<ObstacleLayer>(); return boost::make_shared<ObstacleLayer>();
} }
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)

View File

@ -25,8 +25,8 @@ unsigned char PreferredLayer::interpretValue(unsigned char value)
} }
// Export factory function // Export factory function
static std::shared_ptr<Layer> create_preferred_plugin() { static boost::shared_ptr<Layer> create_preferred_plugin() {
return std::make_shared<PreferredLayer>(); return boost::make_shared<PreferredLayer>();
} }
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)

View File

@ -361,8 +361,8 @@ void StaticLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int
} }
// Export factory function // Export factory function
static std::shared_ptr<Layer> create_static_plugin() { static boost::shared_ptr<Layer> create_static_plugin() {
return std::make_shared<StaticLayer>(); return boost::make_shared<StaticLayer>();
} }
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)

View File

@ -23,8 +23,8 @@ unsigned char UnPreferredLayer::interpretValue(unsigned char value)
} }
// Export factory function // Export factory function
static std::shared_ptr<Layer> create_unpreferred_plugin() { static boost::shared_ptr<Layer> create_unpreferred_plugin() {
return std::make_shared<UnPreferredLayer>(); return boost::make_shared<UnPreferredLayer>();
} }
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)

View File

@ -450,8 +450,8 @@ void VoxelLayer::updateOrigin(double new_origin_x, double new_origin_y)
} }
// Export factory function // Export factory function
static std::shared_ptr<Layer> create_voxel_plugin() { static boost::shared_ptr<Layer> create_voxel_plugin() {
return std::make_shared<VoxelLayer>(); return boost::make_shared<VoxelLayer>();
} }
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias) // Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)

View File

@ -85,7 +85,7 @@ namespace costmap_2d
boost::unique_lock<Costmap2D::mutex_t> lock(*(costmap_.getMutex())); boost::unique_lock<Costmap2D::mutex_t> lock(*(costmap_.getMutex()));
size_locked_ = size_locked; size_locked_ = size_locked;
costmap_.resizeMap(size_x, size_y, resolution, origin_x, origin_y); costmap_.resizeMap(size_x, size_y, resolution, origin_x, origin_y);
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); for (vector<boost::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin) ++plugin)
{ {
(*plugin)->matchSize(); (*plugin)->matchSize();
@ -112,7 +112,7 @@ namespace costmap_2d
minx_ = miny_ = 1e30; minx_ = miny_ = 1e30;
maxx_ = maxy_ = -1e30; maxx_ = maxy_ = -1e30;
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); for (vector<boost::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin) ++plugin)
{ {
if (!(*plugin)->isEnabled()) if (!(*plugin)->isEnabled())
@ -148,7 +148,7 @@ namespace costmap_2d
costmap_.resetMap(x0, y0, xn, yn); costmap_.resetMap(x0, y0, xn, yn);
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); for (vector<boost::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin) ++plugin)
{ {
if ((*plugin)->isEnabled()) if ((*plugin)->isEnabled())
@ -166,7 +166,7 @@ namespace costmap_2d
bool LayeredCostmap::isCurrent() bool LayeredCostmap::isCurrent()
{ {
current_ = true; current_ = true;
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); for (vector<boost::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin) ++plugin)
{ {
if ((*plugin)->isEnabled()) if ((*plugin)->isEnabled())
@ -180,7 +180,7 @@ namespace costmap_2d
footprint_ = footprint_spec; footprint_ = footprint_spec;
costmap_2d::calculateMinAndMaxDistances(footprint_spec, inscribed_radius_, circumscribed_radius_); costmap_2d::calculateMinAndMaxDistances(footprint_spec, inscribed_radius_, circumscribed_radius_);
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end(); for (vector<boost::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin) ++plugin)
{ {
(*plugin)->onFootprintChanged(); (*plugin)->onFootprintChanged();

View File

@ -2,6 +2,7 @@
#include <costmap_2d/cost_values.h> #include <costmap_2d/cost_values.h>
#include <gtest/gtest.h> #include <gtest/gtest.h>
#include <tf3/buffer_core.h> #include <tf3/buffer_core.h>
#include <geometry_msgs/PoseWithCovariance.h>
namespace costmap_2d { namespace costmap_2d {