This commit is contained in:
2025-12-10 09:10:17 +07:00
parent b41d614d1b
commit 33afdfcc5c
24 changed files with 1847 additions and 347 deletions

View File

@@ -7,6 +7,7 @@
#include <move_base/move_base.h>
#include <cmath>
#include <stdexcept>
#include <cstdlib>
#include <xmlrpcpp/XmlRpcValue.h>
#include <data_convert/data_convert.h>
#include <tf3_geometry_msgs/tf3_geometry_msgs.h>
@@ -69,19 +70,20 @@ void move_base::MoveBase::initialize(TFListenerPtr tf)
if (!initialized_)
{
tf_ = tf;
private_nh_ = robot::NodeHandle("~");
// NodeHandle("~") will automatically load YAML files from config directory
robot::NodeHandle nh("~");
private_nh_ = nh;
printf("[%s:%d] private_nh_.getNamespace(): %s\n", __FILE__, __LINE__, private_nh_.getNamespace().c_str());
recovery_trigger_ = PLANNING_R;
// get some parameters that will be global to the move base node
printf("[%s:%d] Getting planner parameters\n", __FILE__, __LINE__);
std::string global_planner;
private_nh_.getParam("base_global_planner", global_planner, std::string("TwoPointsPlanner"));
std::string local_planner;
private_nh_.getParam("base_local_planner", local_planner, std::string(""));
std::string global_planner, local_planner;
private_nh_.getParam("base_global_planner", global_planner, std::string(""));
printf("[%s:%d] global_planner: %s\n", __FILE__, __LINE__, global_planner.c_str());
private_nh_.getParam("base_local_planner", local_planner, std::string(""));
printf("[%s:%d] local_planner: %s\n", __FILE__, __LINE__, local_planner.c_str());
// Handle nested YAML nodes for costmap config
std::string robot_base_frame;
private_nh_.getParam("robot_base_frame", robot_base_frame, std::string("base_footprint"));