mirror of
https://github.com/modelec/modelec-marcel-ROS.git
synced 2026-01-18 16:47:43 +01:00
c++
This commit is contained in:
@@ -16,7 +16,7 @@ find_package(ament_index_cpp REQUIRED)
|
||||
find_package(modelec_interfaces REQUIRED)
|
||||
find_package(modelec_utils REQUIRED)
|
||||
|
||||
add_executable(strat_fsm src/strat_fms.cpp src/navigation_helper.cpp src/pathfinding.cpp src/action_executor.cpp src/mission_manager.cpp src/missions/prepare_concert_mission.cpp src/missions/promotion_mission.cpp src/missions/go_home_mission.cpp src/obstacle.cpp src/config.cpp)
|
||||
add_executable(strat_fsm src/strat_fms.cpp src/navigation_helper.cpp src/pathfinding.cpp src/action_executor.cpp src/mission_manager.cpp src/missions/prepare_concert_mission.cpp src/missions/promotion_mission.cpp src/missions/go_home_mission.cpp src/obstacle.cpp)
|
||||
ament_target_dependencies(strat_fsm rclcpp std_msgs std_srvs modelec_interfaces ament_index_cpp)
|
||||
target_link_libraries(strat_fsm modelec_utils::modelec_utils tinyxml2::tinyxml2)
|
||||
target_include_directories(strat_fsm PUBLIC
|
||||
@@ -24,7 +24,7 @@ target_include_directories(strat_fsm PUBLIC
|
||||
$<INSTALL_INTERFACE:include>
|
||||
)
|
||||
|
||||
add_executable(enemy_manager src/enemy_manager.cpp src/config.cpp)
|
||||
add_executable(enemy_manager src/enemy_manager.cpp)
|
||||
ament_target_dependencies(enemy_manager rclcpp std_msgs sensor_msgs std_srvs modelec_interfaces ament_index_cpp)
|
||||
target_link_libraries(enemy_manager modelec_utils::modelec_utils tinyxml2::tinyxml2)
|
||||
target_include_directories(enemy_manager PUBLIC
|
||||
|
||||
@@ -24,6 +24,53 @@ namespace Modelec
|
||||
static inline std::unordered_map<std::string, std::string> values_;
|
||||
};
|
||||
|
||||
inline bool Config::load(const std::string& filepath)
|
||||
{
|
||||
tinyxml2::XMLDocument doc;
|
||||
if (doc.LoadFile(filepath.c_str()) != tinyxml2::XML_SUCCESS) {
|
||||
RCLCPP_ERROR(rclcpp::get_logger("Config"), "Failed to load XML file: %s", doc.ErrorName());
|
||||
return false;
|
||||
}
|
||||
|
||||
auto* root = doc.RootElement();
|
||||
if (!root)
|
||||
{
|
||||
RCLCPP_ERROR(rclcpp::get_logger("Config"), "No root element found in XML file");
|
||||
return false;
|
||||
}
|
||||
|
||||
parseNode(root, "");
|
||||
return true;
|
||||
}
|
||||
|
||||
inline void Config::parseNode(tinyxml2::XMLElement* element, const std::string& prefix) {
|
||||
std::string key_prefix = prefix.empty() ? element->Name() : prefix + "." + element->Name();
|
||||
|
||||
const char* text = element->GetText();
|
||||
if (text && std::string(text).find_first_not_of(" \n\t") != std::string::npos) {
|
||||
values_[key_prefix] = text;
|
||||
}
|
||||
|
||||
const tinyxml2::XMLAttribute* attr = element->FirstAttribute();
|
||||
while (attr) {
|
||||
std::string attr_key = key_prefix + "@" + attr->Name();
|
||||
values_[attr_key] = attr->Value();
|
||||
attr = attr->Next();
|
||||
}
|
||||
|
||||
for (tinyxml2::XMLElement* child = element->FirstChildElement(); child; child = child->NextSiblingElement()) {
|
||||
parseNode(child, key_prefix);
|
||||
}
|
||||
}
|
||||
|
||||
inline void Config::printAll()
|
||||
{
|
||||
RCLCPP_INFO(rclcpp::get_logger("Config"), "Loaded %zu configuration values", values_.size());
|
||||
|
||||
for (const auto& pair : values_) {
|
||||
RCLCPP_INFO(rclcpp::get_logger("Config"), "%s: %s", pair.first.c_str(), pair.second.c_str());
|
||||
}
|
||||
}
|
||||
|
||||
template<typename T>
|
||||
T Config::get(const std::string& key, const T& default_value) {
|
||||
|
||||
@@ -1,52 +0,0 @@
|
||||
#include <modelec_strat/config.hpp>
|
||||
|
||||
namespace Modelec
|
||||
{
|
||||
bool Config::load(const std::string& filepath)
|
||||
{
|
||||
tinyxml2::XMLDocument doc;
|
||||
if (doc.LoadFile(filepath.c_str()) != tinyxml2::XML_SUCCESS) {
|
||||
RCLCPP_ERROR(rclcpp::get_logger("Config"), "Failed to load XML file: %s", doc.ErrorName());
|
||||
return false;
|
||||
}
|
||||
|
||||
auto* root = doc.RootElement();
|
||||
if (!root)
|
||||
{
|
||||
RCLCPP_ERROR(rclcpp::get_logger("Config"), "No root element found in XML file");
|
||||
return false;
|
||||
}
|
||||
|
||||
parseNode(root, "");
|
||||
return true;
|
||||
}
|
||||
|
||||
void Config::parseNode(tinyxml2::XMLElement* element, const std::string& prefix) {
|
||||
std::string key_prefix = prefix.empty() ? element->Name() : prefix + "." + element->Name();
|
||||
|
||||
const char* text = element->GetText();
|
||||
if (text && std::string(text).find_first_not_of(" \n\t") != std::string::npos) {
|
||||
values_[key_prefix] = text;
|
||||
}
|
||||
|
||||
const tinyxml2::XMLAttribute* attr = element->FirstAttribute();
|
||||
while (attr) {
|
||||
std::string attr_key = key_prefix + "@" + attr->Name();
|
||||
values_[attr_key] = attr->Value();
|
||||
attr = attr->Next();
|
||||
}
|
||||
|
||||
for (tinyxml2::XMLElement* child = element->FirstChildElement(); child; child = child->NextSiblingElement()) {
|
||||
parseNode(child, key_prefix);
|
||||
}
|
||||
}
|
||||
|
||||
void Config::printAll()
|
||||
{
|
||||
RCLCPP_INFO(rclcpp::get_logger("Config"), "Loaded %zu configuration values", values_.size());
|
||||
|
||||
for (const auto& pair : values_) {
|
||||
RCLCPP_INFO(rclcpp::get_logger("Config"), "%s: %s", pair.first.c_str(), pair.second.c_str());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user