update file voxel_layer
This commit is contained in:
@@ -36,12 +36,12 @@ void CriticalLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, i
|
||||
}
|
||||
|
||||
// Export factory function
|
||||
static PluginStaticLayerPtr create_critical_plugin() {
|
||||
static PluginLayerPtr create_critical_plugin() {
|
||||
return std::make_shared<CriticalLayer>();
|
||||
}
|
||||
|
||||
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||
BOOST_DLL_ALIAS(create_critical_plugin, create_plugin_static_layer)
|
||||
BOOST_DLL_ALIAS(create_critical_plugin, create_plugin)
|
||||
|
||||
|
||||
}
|
||||
@@ -429,10 +429,10 @@ namespace costmap_2d
|
||||
}
|
||||
|
||||
// Export factory function
|
||||
static PluginStaticLayerPtr create_directional_plugin() {
|
||||
static PluginLayerPtr create_directional_plugin() {
|
||||
return std::make_shared<DirectionalLayer>();
|
||||
}
|
||||
|
||||
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||
BOOST_DLL_ALIAS(create_directional_plugin, create_plugin_static_layer)
|
||||
BOOST_DLL_ALIAS(create_directional_plugin, create_plugin)
|
||||
}
|
||||
@@ -47,7 +47,7 @@ void InflationLayer::onInitialize()
|
||||
getParams();
|
||||
}
|
||||
|
||||
matchSize();
|
||||
InflationLayer::matchSize();
|
||||
}
|
||||
|
||||
bool InflationLayer::getParams()
|
||||
@@ -350,12 +350,19 @@ void InflationLayer::setInflationParameters(double inflation_radius, double cost
|
||||
}
|
||||
}
|
||||
|
||||
void InflationLayer::handleImpl(const void* data,
|
||||
const std::type_info& info,
|
||||
const std::string& source)
|
||||
{
|
||||
printf("This function is not available!\n");
|
||||
}
|
||||
|
||||
// Export factory function
|
||||
static PluginLayerPtr create_inflation_plugin() {
|
||||
return std::make_shared<InflationLayer>();
|
||||
}
|
||||
|
||||
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||
BOOST_DLL_ALIAS(create_inflation_plugin, create_plugin_layer)
|
||||
BOOST_DLL_ALIAS(create_inflation_plugin, create_plugin)
|
||||
|
||||
} // namespace costmap_2d
|
||||
|
||||
@@ -19,7 +19,6 @@ namespace costmap_2d
|
||||
void ObstacleLayer::onInitialize()
|
||||
{
|
||||
rolling_window_ = layered_costmap_->isRolling();
|
||||
|
||||
|
||||
ObstacleLayer::matchSize();
|
||||
current_ = true;
|
||||
@@ -103,7 +102,7 @@ bool ObstacleLayer::getParams()
|
||||
|
||||
printf(
|
||||
"Created an observation buffer for topic %s, global frame: %s, "
|
||||
"expected update rate: %.2f, observation persistence: %.2f",
|
||||
"expected update rate: %.2f, observation persistence: %.2f\n",
|
||||
topic.c_str(), global_frame_.c_str(), expected_update_rate, observation_keep_time);
|
||||
|
||||
}
|
||||
@@ -517,7 +516,7 @@ void ObstacleLayer::reset()
|
||||
}
|
||||
|
||||
// Export factory function
|
||||
static PluginCostmapLayerPtr create_obstacle_plugin() {
|
||||
static PluginLayerPtr create_obstacle_plugin() {
|
||||
return std::make_shared<ObstacleLayer>();
|
||||
}
|
||||
|
||||
|
||||
@@ -25,11 +25,11 @@ unsigned char PreferredLayer::interpretValue(unsigned char value)
|
||||
}
|
||||
|
||||
// Export factory function
|
||||
static PluginStaticLayerPtr create_preferred_plugin() {
|
||||
static PluginLayerPtr create_preferred_plugin() {
|
||||
return std::make_shared<PreferredLayer>();
|
||||
}
|
||||
|
||||
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||
BOOST_DLL_ALIAS(create_preferred_plugin, create_plugin_static_layer)
|
||||
BOOST_DLL_ALIAS(create_preferred_plugin, create_plugin)
|
||||
|
||||
}
|
||||
@@ -325,7 +325,7 @@ void StaticLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int
|
||||
}
|
||||
|
||||
// Export factory function
|
||||
static PluginCostmapLayerPtr create_static_plugin() {
|
||||
static PluginLayerPtr create_static_plugin() {
|
||||
return std::make_shared<StaticLayer>();
|
||||
}
|
||||
|
||||
|
||||
@@ -23,11 +23,11 @@ unsigned char UnPreferredLayer::interpretValue(unsigned char value)
|
||||
}
|
||||
|
||||
// Export factory function
|
||||
static PluginStaticLayerPtr create_unpreferred_plugin() {
|
||||
static PluginLayerPtr create_unpreferred_plugin() {
|
||||
return std::make_shared<UnPreferredLayer>();
|
||||
}
|
||||
|
||||
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||
BOOST_DLL_ALIAS(create_unpreferred_plugin, create_plugin_static_layer)
|
||||
BOOST_DLL_ALIAS(create_unpreferred_plugin, create_plugin)
|
||||
|
||||
}
|
||||
@@ -445,11 +445,11 @@ void VoxelLayer::matchSize()
|
||||
// }
|
||||
|
||||
// Export factory function
|
||||
static PluginObstacleLayerPtr create_voxel_plugin() {
|
||||
static PluginLayerPtr create_voxel_plugin() {
|
||||
return std::make_shared<VoxelLayer>();
|
||||
}
|
||||
|
||||
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||
BOOST_DLL_ALIAS(create_voxel_plugin, create_obstacle_plugin)
|
||||
BOOST_DLL_ALIAS(create_voxel_plugin, create_plugin)
|
||||
|
||||
} // namespace costmap_2d
|
||||
|
||||
Reference in New Issue
Block a user