replace std::shared_ptr to boost::shared_ptr
This commit is contained in:
parent
f37bccd02f
commit
af43332b28
|
|
@ -253,7 +253,7 @@ private:
|
|||
void readFootprintFromConfig(const std::vector<geometry_msgs::Point> &new_footprint,
|
||||
const std::vector<geometry_msgs::Point> &old_footprint,
|
||||
const double &robot_radius);
|
||||
std::vector<std::function<PluginLayerPtr()>> creators_;
|
||||
std::vector<boost::function<PluginLayerPtr()>> creators_;
|
||||
void checkMovement();
|
||||
void mapUpdateLoop(double frequency);
|
||||
bool map_update_thread_shutdown_;
|
||||
|
|
|
|||
|
|
@ -163,7 +163,7 @@ private:
|
|||
std::vector<geometry_msgs::Point> footprint_spec_;
|
||||
};
|
||||
|
||||
using PluginLayerPtr = std::shared_ptr<Layer>;
|
||||
using PluginLayerPtr = boost::shared_ptr<Layer>;
|
||||
|
||||
} // namespace costmap_2d
|
||||
|
||||
|
|
|
|||
|
|
@ -104,12 +104,12 @@ public:
|
|||
return costmap_.getDefaultValue() == costmap_2d::NO_INFORMATION;
|
||||
}
|
||||
|
||||
std::vector<std::shared_ptr<Layer> >* getPlugins()
|
||||
std::vector<boost::shared_ptr<Layer> >* getPlugins()
|
||||
{
|
||||
return &plugins_;
|
||||
}
|
||||
|
||||
void addPlugin(std::shared_ptr<Layer> plugin)
|
||||
void addPlugin(boost::shared_ptr<Layer> plugin)
|
||||
{
|
||||
plugins_.push_back(plugin);
|
||||
}
|
||||
|
|
@ -164,7 +164,7 @@ private:
|
|||
double minx_, miny_, maxx_, maxy_;
|
||||
unsigned int bx0_, bxn_, by0_, byn_;
|
||||
|
||||
std::vector<std::shared_ptr<Layer> > plugins_;
|
||||
std::vector<boost::shared_ptr<Layer> > plugins_;
|
||||
|
||||
bool initialized_;
|
||||
bool size_locked_;
|
||||
|
|
|
|||
|
|
@ -36,8 +36,8 @@ void CriticalLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, i
|
|||
}
|
||||
|
||||
// Export factory function
|
||||
static std::shared_ptr<Layer> create_critical_plugin() {
|
||||
return std::make_shared<CriticalLayer>();
|
||||
static boost::shared_ptr<Layer> create_critical_plugin() {
|
||||
return boost::make_shared<CriticalLayer>();
|
||||
}
|
||||
|
||||
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||
|
|
|
|||
|
|
@ -428,8 +428,8 @@ namespace costmap_2d
|
|||
}
|
||||
|
||||
// Export factory function
|
||||
static std::shared_ptr<Layer> create_directional_plugin() {
|
||||
return std::make_shared<DirectionalLayer>();
|
||||
static boost::shared_ptr<Layer> create_directional_plugin() {
|
||||
return boost::make_shared<DirectionalLayer>();
|
||||
}
|
||||
|
||||
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||
|
|
|
|||
|
|
@ -397,8 +397,8 @@ void InflationLayer::handleImpl(const void* data,
|
|||
|
||||
|
||||
// Export factory function
|
||||
static std::shared_ptr<Layer> create_inflation_plugin() {
|
||||
return std::make_shared<InflationLayer>();
|
||||
static boost::shared_ptr<Layer> create_inflation_plugin() {
|
||||
return boost::make_shared<InflationLayer>();
|
||||
}
|
||||
|
||||
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||
|
|
|
|||
|
|
@ -555,8 +555,8 @@ void ObstacleLayer::reset()
|
|||
}
|
||||
|
||||
// Export factory function
|
||||
static std::shared_ptr<Layer> create_obstacle_plugin() {
|
||||
return std::make_shared<ObstacleLayer>();
|
||||
static boost::shared_ptr<Layer> create_obstacle_plugin() {
|
||||
return boost::make_shared<ObstacleLayer>();
|
||||
}
|
||||
|
||||
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||
|
|
|
|||
|
|
@ -25,8 +25,8 @@ unsigned char PreferredLayer::interpretValue(unsigned char value)
|
|||
}
|
||||
|
||||
// Export factory function
|
||||
static std::shared_ptr<Layer> create_preferred_plugin() {
|
||||
return std::make_shared<PreferredLayer>();
|
||||
static boost::shared_ptr<Layer> create_preferred_plugin() {
|
||||
return boost::make_shared<PreferredLayer>();
|
||||
}
|
||||
|
||||
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||
|
|
|
|||
|
|
@ -361,8 +361,8 @@ void StaticLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int
|
|||
}
|
||||
|
||||
// Export factory function
|
||||
static std::shared_ptr<Layer> create_static_plugin() {
|
||||
return std::make_shared<StaticLayer>();
|
||||
static boost::shared_ptr<Layer> create_static_plugin() {
|
||||
return boost::make_shared<StaticLayer>();
|
||||
}
|
||||
|
||||
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||
|
|
|
|||
|
|
@ -23,8 +23,8 @@ unsigned char UnPreferredLayer::interpretValue(unsigned char value)
|
|||
}
|
||||
|
||||
// Export factory function
|
||||
static std::shared_ptr<Layer> create_unpreferred_plugin() {
|
||||
return std::make_shared<UnPreferredLayer>();
|
||||
static boost::shared_ptr<Layer> create_unpreferred_plugin() {
|
||||
return boost::make_shared<UnPreferredLayer>();
|
||||
}
|
||||
|
||||
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||
|
|
|
|||
|
|
@ -450,8 +450,8 @@ void VoxelLayer::updateOrigin(double new_origin_x, double new_origin_y)
|
|||
}
|
||||
|
||||
// Export factory function
|
||||
static std::shared_ptr<Layer> create_voxel_plugin() {
|
||||
return std::make_shared<VoxelLayer>();
|
||||
static boost::shared_ptr<Layer> create_voxel_plugin() {
|
||||
return boost::make_shared<VoxelLayer>();
|
||||
}
|
||||
|
||||
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||
|
|
|
|||
|
|
@ -85,7 +85,7 @@ namespace costmap_2d
|
|||
boost::unique_lock<Costmap2D::mutex_t> lock(*(costmap_.getMutex()));
|
||||
size_locked_ = size_locked;
|
||||
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)->matchSize();
|
||||
|
|
@ -112,7 +112,7 @@ namespace costmap_2d
|
|||
minx_ = miny_ = 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)
|
||||
{
|
||||
if (!(*plugin)->isEnabled())
|
||||
|
|
@ -148,7 +148,7 @@ namespace costmap_2d
|
|||
|
||||
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)
|
||||
{
|
||||
if ((*plugin)->isEnabled())
|
||||
|
|
@ -166,7 +166,7 @@ namespace costmap_2d
|
|||
bool LayeredCostmap::isCurrent()
|
||||
{
|
||||
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)
|
||||
{
|
||||
if ((*plugin)->isEnabled())
|
||||
|
|
@ -180,7 +180,7 @@ namespace costmap_2d
|
|||
footprint_ = footprint_spec;
|
||||
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)->onFootprintChanged();
|
||||
|
|
|
|||
|
|
@ -2,6 +2,7 @@
|
|||
#include <costmap_2d/cost_values.h>
|
||||
#include <gtest/gtest.h>
|
||||
#include <tf3/buffer_core.h>
|
||||
#include <geometry_msgs/PoseWithCovariance.h>
|
||||
|
||||
namespace costmap_2d {
|
||||
|
||||
|
|
|
|||
Loading…
Reference in New Issue
Block a user