Compare commits

...

4 Commits

10 changed files with 12 additions and 18 deletions

View File

@@ -71,8 +71,7 @@ target_link_libraries(costmap_2d
xmlrpcpp # XMLRPC xmlrpcpp # XMLRPC
yaml-cpp yaml-cpp
dl dl
robot::node_handle robot_cpp
robot::console
) )
# --- Include directories cho target --- # --- Include directories cho target ---
@@ -127,11 +126,9 @@ target_link_libraries(plugins
${Boost_LIBRARIES} ${Boost_LIBRARIES}
yaml-cpp yaml-cpp
robot_time robot_time
robot::node_handle robot_cpp
robot::console
) )
# --- Option để bật/tắt test --- # --- Option để bật/tắt test ---
option(BUILD_COSTMAP_TESTS "Build costmap_2d test executables" ON) option(BUILD_COSTMAP_TESTS "Build costmap_2d test executables" ON)

View File

@@ -41,7 +41,7 @@ static boost::shared_ptr<Layer> create_critical_plugin() {
} }
// 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)
BOOST_DLL_ALIAS(create_critical_plugin, create_critical_layer) BOOST_DLL_ALIAS(create_critical_plugin, CriticalLayer)
} }

View File

@@ -433,5 +433,5 @@ namespace costmap_2d
} }
// 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)
BOOST_DLL_ALIAS(create_directional_plugin, create_directional_layer) BOOST_DLL_ALIAS(create_directional_plugin, DirectionalLayer)
} }

View File

@@ -414,6 +414,6 @@ static boost::shared_ptr<Layer> create_inflation_plugin() {
} }
// 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)
BOOST_DLL_ALIAS(create_inflation_plugin, create_inflation_layer) BOOST_DLL_ALIAS(create_inflation_plugin, InflationLayer)
} // namespace costmap_2d } // namespace costmap_2d

View File

@@ -595,6 +595,6 @@ static boost::shared_ptr<Layer> create_obstacle_plugin() {
} }
// 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)
BOOST_DLL_ALIAS(create_obstacle_plugin, create_obstacle_layer) BOOST_DLL_ALIAS(create_obstacle_plugin, ObstacleLayer)
} // namespace costmap_2d } // namespace costmap_2d

View File

@@ -30,6 +30,6 @@ static boost::shared_ptr<Layer> create_preferred_plugin() {
} }
// 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)
BOOST_DLL_ALIAS(create_preferred_plugin, create_preferred_layer) BOOST_DLL_ALIAS(create_preferred_plugin, PreferredLayer)
} }

View File

@@ -387,6 +387,6 @@ static boost::shared_ptr<Layer> create_static_plugin() {
} }
// 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)
BOOST_DLL_ALIAS(create_static_plugin, create_static_layer) BOOST_DLL_ALIAS(create_static_plugin, StaticLayer)
} // namespace costmap_2d } // namespace costmap_2d

View File

@@ -28,6 +28,6 @@ static boost::shared_ptr<Layer> create_unpreferred_plugin() {
} }
// 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)
BOOST_DLL_ALIAS(create_unpreferred_plugin, create_unpreferred_layer) BOOST_DLL_ALIAS(create_unpreferred_plugin, UnPreferredLayer)
} }

View File

@@ -102,7 +102,7 @@ bool VoxelLayer::getParams(const std::string& config_file_name, robot::NodeHandl
if (nh.hasParam("unknown_threshold")) if (nh.hasParam("unknown_threshold"))
{ {
nh.getParam("unknown_threshold", unknown_threshold); nh.getParam("unknown_threshold", unknown_threshold);
unknown_threshold_ = unknown_threshold; unknown_threshold_ = unknown_threshold + (VOXEL_BITS - size_z_);
} }
if (nh.hasParam("mark_threshold")) if (nh.hasParam("mark_threshold"))
{ {
@@ -111,9 +111,6 @@ bool VoxelLayer::getParams(const std::string& config_file_name, robot::NodeHandl
} }
if (nh.hasParam("combination_method")) if (nh.hasParam("combination_method"))
nh.getParam("combination_method", combination_method_); nh.getParam("combination_method", combination_method_);
this->matchSize(); this->matchSize();
@@ -491,6 +488,6 @@ static boost::shared_ptr<Layer> create_voxel_plugin() {
} }
// 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)
BOOST_DLL_ALIAS(create_voxel_plugin, create_voxel_layer) BOOST_DLL_ALIAS(create_voxel_plugin, VoxelLayer)
} // namespace costmap_2d } // namespace costmap_2d

View File

@@ -219,7 +219,7 @@ void Costmap2DROBOT::getParams(const std::string& config_file_name, robot::NodeH
} }
catch (std::exception &ex) catch (std::exception &ex)
{ {
printf("Failed to create the %s, are you sure it is properly registered and that the containing library is built? Exception: %s\n", info.name.c_str(), ex.what()); robot::log_error("Failed to create the %s, are you sure it is properly registered and that the containing library is built? Exception: %s\n", info.name.c_str(), ex.what());
return; return;
} }
} }