This commit is contained in:
2026-02-05 16:59:14 +07:00
parent b0047b61a9
commit 9c436fdae6
3 changed files with 10 additions and 10 deletions

View File

@@ -250,11 +250,6 @@ namespace amr_control
sensor_converter_ptr_ = std::make_shared<amr_control::SensorConverter>(nh, move_base_ptr_);
move_base_ptr_->initialize(tf_core_ptr_);
// Initialize costmap publisher for RViz visualization
robot::log_info("[%s:%d]\n Initializing costmap publisher...", __FILE__, __LINE__);
amr_publisher_ptr_ = std::make_shared<amr_control::AmrPublisher>(nh, move_base_ptr_);
amr_subscriber_ptr_ = std::make_shared<amr_control::AmrSubscriber>(nh, move_base_ptr_);
ros::Rate r(3);
do
{
@@ -262,6 +257,11 @@ namespace amr_control
ros::spinOnce();
} while (ros::ok() && !move_base_ptr_->getFeedback()->is_ready);
// Initialize costmap publisher for RViz visualization
robot::log_info("[%s:%d]\n Initializing costmap publisher...", __FILE__, __LINE__);
amr_publisher_ptr_ = std::make_shared<amr_control::AmrPublisher>(nh, move_base_ptr_);
amr_subscriber_ptr_ = std::make_shared<amr_control::AmrSubscriber>(nh, move_base_ptr_);
if (move_base_ptr_ != nullptr &&
move_base_ptr_->getFeedback() != nullptr &&
move_base_ptr_->getFeedback()->is_ready)

View File

@@ -4,10 +4,10 @@
amr_control::AmrSubscriber::AmrSubscriber(ros::NodeHandle &nh, robot::move_base_core::BaseNavigation::Ptr move_base_ptr)
: nh_(nh), move_base_ptr_(move_base_ptr)
{
robot::log_info("[%s:%d] Initializing AmrSubscriber namespace: %s", __FILE__, __LINE__, nh_.getNamespace().c_str());
ros::NodeHandle nh_move_base;
move_base_simple_sub_ = nh_move_base.subscribe("/move_base_simple/goal", 1, &AmrSubscriber::moveBaseSimpleCallback, this);
odometry_sub_ = nh_move_base.subscribe("/odom", 1, &AmrSubscriber::odometryCallback, this);
robot::log_info("[%s:%d] Initializing AmrSubscriber namespace: %s", __FILE__, __LINE__, nh_.getNamespace().c_str());
ros::NodeHandle nh_move_base;
move_base_simple_sub_ = nh_move_base.subscribe("/move_base_simple/goal", 1, &AmrSubscriber::moveBaseSimpleCallback, this);
odometry_sub_ = nh_move_base.subscribe("/odom", 1, &AmrSubscriber::odometryCallback, this);
}