Skip to content
Snippets Groups Projects
Unverified Commit 63afa48d authored by Steven Macenski's avatar Steven Macenski Committed by GitHub
Browse files

Merge pull request #1234 from SteveMacenski/audit_shared

convert candidate shared ptrs to unique ptrs
parents a9891189 9a62d5a6
No related branches found
No related tags found
No related merge requests found
......@@ -71,7 +71,7 @@ protected:
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
......
......@@ -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
......
......@@ -104,10 +104,10 @@ public:
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>(
......@@ -147,8 +147,8 @@ protected:
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_;
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment