Skip to content

Commit

Permalink
Refactoring costmap_2d_ros.cpp
Browse files Browse the repository at this point in the history
  • Loading branch information
VladyslavHrynchak200204 committed Jul 25, 2024
1 parent a0c6e34 commit 07cc3cb
Showing 1 changed file with 1 addition and 2 deletions.
3 changes: 1 addition & 2 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -225,8 +225,6 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
footprint_pub_ = create_publisher<geometry_msgs::msg::PolygonStamped>(
"published_footprint", rclcpp::SystemDefaultsQoS());

get_parameter("map_vis_y", map_vis_y_);

costmap_publisher_ = std::make_unique<Costmap2DPublisher>(
shared_from_this(),
layered_costmap_->getCostmap(), global_frame_,
Expand Down Expand Up @@ -390,6 +388,7 @@ Costmap2DROS::getParameters()

// Get all of the required parameters
get_parameter("always_send_full_costmap", always_send_full_costmap_);
get_parameter("map_vis_y", map_vis_y_);
get_parameter("footprint", footprint_);
get_parameter("footprint_padding", footprint_padding_);
get_parameter("global_frame", global_frame_);
Expand Down

0 comments on commit 07cc3cb

Please sign in to comment.