Skip to content

Commit

Permalink
Change all shared_ptr references to shared_ptr (#2976)
Browse files Browse the repository at this point in the history
* Change all shared_ptr references to shared_ptr

* Update simple_smoother.cpp

Co-authored-by: Steve Macenski <[email protected]>
  • Loading branch information
naiveHobo and SteveMacenski authored May 31, 2022
1 parent 80d7d0a commit 4d596b9
Show file tree
Hide file tree
Showing 13 changed files with 32 additions and 32 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -58,9 +58,9 @@ class ConstrainedSmoother : public nav2_core::Smoother
*/
void configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
std::string name, const std::shared_ptr<tf2_ros::Buffer> & tf,
const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> & costmap_sub,
const std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> & footprint_sub) override;
std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub,
std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub) override;

/**
* @brief Cleanup controller state machine
Expand Down
6 changes: 3 additions & 3 deletions nav2_constrained_smoother/src/constrained_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,9 @@ namespace nav2_constrained_smoother

void ConstrainedSmoother::configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
std::string name, const std::shared_ptr<tf2_ros::Buffer> & tf,
const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> & costmap_sub,
const std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> &)
std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub,
std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>)
{
auto node = parent.lock();
if (!node) {
Expand Down
4 changes: 2 additions & 2 deletions nav2_core/include/nav2_core/controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,8 +74,8 @@ class Controller
*/
virtual void configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr &,
std::string name, const std::shared_ptr<tf2_ros::Buffer> &,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> &) = 0;
std::string name, std::shared_ptr<tf2_ros::Buffer>,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS>) = 0;

/**
* @brief Method to cleanup resources.
Expand Down
6 changes: 3 additions & 3 deletions nav2_core/include/nav2_core/smoother.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,9 +47,9 @@ class Smoother

virtual void configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr &,
std::string name, const std::shared_ptr<tf2_ros::Buffer> &,
const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> &,
const std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> &) = 0;
std::string name, std::shared_ptr<tf2_ros::Buffer>,
std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>) = 0;

/**
* @brief Method to cleanup resources.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,8 +68,8 @@ class DWBLocalPlanner : public nav2_core::Controller

void configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
std::string name, const std::shared_ptr<tf2_ros::Buffer> & tf,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> & costmap_ros) override;
std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;

virtual ~DWBLocalPlanner() {}

Expand Down
4 changes: 2 additions & 2 deletions nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +67,8 @@ DWBLocalPlanner::DWBLocalPlanner()

void DWBLocalPlanner::configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
std::string name, const std::shared_ptr<tf2_ros::Buffer> & tf,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> & costmap_ros)
std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
{
node_ = parent;
auto node = node_.lock();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,8 @@ class RegulatedPurePursuitController : public nav2_core::Controller
*/
void configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
std::string name, const std::shared_ptr<tf2_ros::Buffer> & tf,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> & costmap_ros) override;
std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;

/**
* @brief Cleanup controller state machine
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,8 @@ namespace nav2_regulated_pure_pursuit_controller

void RegulatedPurePursuitController::configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
std::string name, const std::shared_ptr<tf2_ros::Buffer> & tf,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> & costmap_ros)
std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
{
auto node = parent.lock();
node_ = parent;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,8 @@ class RotationShimController : public nav2_core::Controller
*/
void configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
std::string name, const std::shared_ptr<tf2_ros::Buffer> & tf,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> & costmap_ros) override;
std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;

/**
* @brief Cleanup controller state machine
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@ RotationShimController::RotationShimController()

void RotationShimController::configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
std::string name, const std::shared_ptr<tf2_ros::Buffer> & tf,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> & costmap_ros)
std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
{
plugin_name_ = name;
node_ = parent;
Expand Down
6 changes: 3 additions & 3 deletions nav2_smoother/include/nav2_smoother/simple_smoother.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,9 +67,9 @@ class SimpleSmoother : public nav2_core::Smoother

void configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr &,
std::string name, const std::shared_ptr<tf2_ros::Buffer> &,
const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> &,
const std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> &) override;
std::string name, std::shared_ptr<tf2_ros::Buffer>,
std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>) override;

/**
* @brief Method to cleanup resources.
Expand Down
6 changes: 3 additions & 3 deletions nav2_smoother/src/simple_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@ using nav2_util::declare_parameter_if_not_declared;

void SimpleSmoother::configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
std::string name, const std::shared_ptr<tf2_ros::Buffer> & /*tf*/,
const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> & costmap_sub,
const std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> & /*footprint_sub*/)
std::string name, std::shared_ptr<tf2_ros::Buffer>/*tf*/,
std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub,
std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>/*footprint_sub*/)
{
costmap_sub_ = costmap_sub;

Expand Down
6 changes: 3 additions & 3 deletions nav2_smoother/test/test_smoother_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,9 @@ class DummySmoother : public nav2_core::Smoother

virtual void configure(
const rclcpp_lifecycle::LifecycleNode::WeakPtr &,
std::string, const std::shared_ptr<tf2_ros::Buffer> &,
const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> &,
const std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> &) {}
std::string, std::shared_ptr<tf2_ros::Buffer>,
std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>) {}

virtual void cleanup() {}

Expand Down

0 comments on commit 4d596b9

Please sign in to comment.