diff --git a/nav2_pure_pursuit_controller/include/nav2_pure_pursuit_controller/pure_pursuit_controller.hpp b/nav2_pure_pursuit_controller/include/nav2_pure_pursuit_controller/pure_pursuit_controller.hpp index e1e8b0e..d7a0212 100644 --- a/nav2_pure_pursuit_controller/include/nav2_pure_pursuit_controller/pure_pursuit_controller.hpp +++ b/nav2_pure_pursuit_controller/include/nav2_pure_pursuit_controller/pure_pursuit_controller.hpp @@ -27,19 +27,19 @@ class PurePursuitController : public nav2_core::Controller ~PurePursuitController() override = default; void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, - std::string name, const std::shared_ptr & tf, - const std::shared_ptr & costmap_ros) override; + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + std::string name, const std::shared_ptr tf, + const std::shared_ptr costmap_ros) override; void cleanup() override; void activate() override; void deactivate() override; void setSpeedLimit(const double & speed_limit, const bool & percentage) override; - + geometry_msgs::msg::TwistStamped computeVelocityCommands( const geometry_msgs::msg::PoseStamped & pose, - const geometry_msgs::msg::Twist & velocity + const geometry_msgs::msg::Twist & velocity, nav2_core::GoalChecker * goal_checker) override; void setPlan(const nav_msgs::msg::Path & path) override; diff --git a/nav2_pure_pursuit_controller/src/pure_pursuit_controller.cpp b/nav2_pure_pursuit_controller/src/pure_pursuit_controller.cpp index 744bcb5..b40f1e6 100644 --- a/nav2_pure_pursuit_controller/src/pure_pursuit_controller.cpp +++ b/nav2_pure_pursuit_controller/src/pure_pursuit_controller.cpp @@ -255,7 +255,7 @@ bool PurePursuitController::transformPose( const rclcpp::Duration & transform_tolerance ) const { - // Implementation taken as is fron nav_2d_utils in nav2_dwb_controller + // Implementation taken as is from nav_2d_utils in nav2_dwb_controller if (in_pose.header.frame_id == frame) { out_pose = in_pose;