Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ class ControllerServer : public nav2_util::LifecycleNode
std::unique_ptr<std::thread> costmap_thread_;

// Publishers and subscribers
std::shared_ptr<nav_2d_utils::OdomSubscriber> odom_sub_;
std::unique_ptr<nav_2d_utils::OdomSubscriber> odom_sub_;
rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::Twist>::SharedPtr vel_publisher_;

// Local Planner Plugin
Expand Down
2 changes: 1 addition & 1 deletion nav2_controller/src/nav2_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
get_parameter("controller_frequency", controller_frequency_);
RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_);

odom_sub_ = std::make_shared<nav_2d_utils::OdomSubscriber>(node);
odom_sub_ = std::make_unique<nav_2d_utils::OdomSubscriber>(node);
vel_publisher_ = create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", 1);

// Create the action server that we implement with our followPath method
Expand Down
8 changes: 4 additions & 4 deletions nav2_recoveries/include/nav2_recoveries/recovery.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,10 +104,10 @@ class Recovery : public nav2_core::Recovery
action_server_ = std::make_unique<ActionServer>(node_, recovery_name_,
std::bind(&Recovery::execute, this));

costmap_sub_ = std::make_shared<nav2_costmap_2d::CostmapSubscriber>(
costmap_sub_ = std::make_unique<nav2_costmap_2d::CostmapSubscriber>(
node_, costmap_topic);

footprint_sub_ = std::make_shared<nav2_costmap_2d::FootprintSubscriber>(
footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
node_, footprint_topic);

collision_checker_ = std::make_unique<nav2_costmap_2d::CollisionChecker>(
Expand Down Expand Up @@ -147,8 +147,8 @@ class Recovery : public nav2_core::Recovery
std::shared_ptr<tf2_ros::Buffer> tf_;
std::unique_ptr<ActionServer> action_server_;

std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
std::unique_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
std::unique_ptr<nav2_costmap_2d::CollisionChecker> collision_checker_;
double cycle_frequency_;
double enabled_;
Expand Down