.. _program_listing_file__tmp_ws_src_SMACC2_smacc2_client_library_nav2z_client_custom_planners_pure_spinning_local_planner_include_pure_spinning_local_planner_pure_spinning_local_planner.hpp: Program Listing for File pure_spinning_local_planner.hpp ======================================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/SMACC2/smacc2_client_library/nav2z_client/custom_planners/pure_spinning_local_planner/include/pure_spinning_local_planner/pure_spinning_local_planner.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2021 RobosoftAI Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. /***************************************************************************************************************** * * Authors: Pablo Inigo Blasco, Brett Aldrich * ******************************************************************************************************************/ #pragma once //#include //#include #include #include #include #include #include #include #include #include typedef double meter; typedef double rad; typedef double rad_s; namespace cl_nav2z { namespace pure_spinning_local_planner { class PureSpinningLocalPlanner : public nav2_core::Controller { public: PureSpinningLocalPlanner(); virtual ~PureSpinningLocalPlanner(); void configure( const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name, const std::shared_ptr tf, const std::shared_ptr costmap_ros) override; void activate() override; void deactivate() override; void cleanup() override; void setPlan(const nav_msgs::msg::Path & path) override; virtual geometry_msgs::msg::TwistStamped computeVelocityCommands( const geometry_msgs::msg::PoseStamped & pose, const geometry_msgs::msg::Twist & velocity, nav2_core::GoalChecker * goal_checker) override; /*deprecated in navigation2*/ bool isGoalReached(); virtual void setSpeedLimit(const double & speed_limit, const bool & percentage) override; private: void updateParameters(); nav2_util::LifecycleNode::SharedPtr nh_; std::string name_; void publishGoalMarker(double x, double y, double phi); std::shared_ptr costmapRos_; std::shared_ptr> goalMarkerPublisher_; std::vector plan_; std::shared_ptr tf_; double k_betta_; bool goalReached_; int currentPoseIndex_; rad yaw_goal_tolerance_; rad intermediate_goal_yaw_tolerance_; rad_s max_angular_z_speed_; double transform_tolerance_; bool use_shortest_angular_distance_; }; } // namespace pure_spinning_local_planner } // namespace cl_nav2z