| 
    SMACC2
    
   | 
 
#include <undo_path_global_planner.hpp>


Public Member Functions | |
| UndoPathGlobalPlanner () | |
| virtual | ~UndoPathGlobalPlanner () | 
| Virtual destructor.   | |
| virtual void | configure (const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) | 
| virtual void | cleanup () | 
| Method to cleanup resources used on shutdown.   | |
| virtual void | activate () | 
| Method to active planner and any threads involved in execution.   | |
| virtual void | deactivate () | 
| Method to deactivate planner and any threads involved in execution.   | |
| virtual nav_msgs::msg::Path | createPlan (const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal) | 
| Method create the plan from a starting and ending goal.   | |
Private Member Functions | |
| void | onForwardTrailMsg (const nav_msgs::msg::Path::SharedPtr trailMessage) | 
| void | publishGoalMarker (const geometry_msgs::msg::Pose &pose, double r, double g, double b) | 
| void | clearGoalMarker () | 
| virtual void | createDefaultUndoPathPlan (const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, std::vector< geometry_msgs::msg::PoseStamped > &plan) | 
Private Attributes | |
| rclcpp_lifecycle::LifecycleNode::SharedPtr | nh_ | 
| rclcpp::Subscription< nav_msgs::msg::Path >::SharedPtr | forwardPathSub_ | 
| rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path >::SharedPtr | planPub_ | 
| rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray >::SharedPtr | markersPub_ | 
| nav_msgs::msg::Path | lastForwardPathMsg_ | 
| std::shared_ptr< nav2_costmap_2d::Costmap2DROS > | costmap_ros_ | 
| stored but almost not used   | |
| double | skip_straight_motion_distance_ | 
| double | puresSpinningRadStep_ | 
| double | transform_tolerance_ | 
| std::string | name_ | 
| std::shared_ptr< tf2_ros::Buffer > | tf_ | 
Definition at line 31 of file undo_path_global_planner.hpp.
| cl_nav2z::undo_path_global_planner::UndoPathGlobalPlanner::UndoPathGlobalPlanner | ( | ) | 
Constructor()
Definition at line 47 of file undo_path_global_planner.cpp.
References skip_straight_motion_distance_, and transform_tolerance_.
      
  | 
  virtual | 
      
  | 
  virtual | 
Method to active planner and any threads involved in execution.
Definition at line 63 of file undo_path_global_planner.cpp.
References markersPub_, nh_, and planPub_.
      
  | 
  virtual | 
Method to cleanup resources used on shutdown.
Definition at line 61 of file undo_path_global_planner.cpp.
References clearGoalMarker().

      
  | 
  private | 
Definition at line 126 of file undo_path_global_planner.cpp.
References costmap_ros_, markersPub_, and nh_.
Referenced by cleanup(), and deactivate().

      
  | 
  virtual | 
| parent | pointer to user's node | 
| name | The name of this planner | 
| tf | A pointer to a TF buffer | 
| costmap_ros | A pointer to the costmap | 
initialize()
Definition at line 83 of file undo_path_global_planner.cpp.
References costmap_ros_, declareOrSet(), forwardPathSub_, markersPub_, name_, nh_, onForwardTrailMsg(), planPub_, tf_, and transform_tolerance_.

      
  | 
  privatevirtual | 
defaultBackwardPath()
Definition at line 188 of file undo_path_global_planner.cpp.
References costmap_ros_, lastForwardPathMsg_, nh_, tf_, and transform_tolerance_.
Referenced by createPlan().

      
  | 
  virtual | 
Method create the plan from a starting and ending goal.
| start | The starting pose of the robot | 
| goal | The goal pose of the robot | 
makePlan()
Definition at line 376 of file undo_path_global_planner.cpp.
References costmap_ros_, createDefaultUndoPathPlan(), lastForwardPathMsg_, nh_, planPub_, publishGoalMarker(), tf_, and transform_tolerance_.

      
  | 
  virtual | 
Method to deactivate planner and any threads involved in execution.
Definition at line 70 of file undo_path_global_planner.cpp.
References clearGoalMarker(), markersPub_, nh_, and planPub_.

      
  | 
  private | 
Definition at line 112 of file undo_path_global_planner.cpp.
References lastForwardPathMsg_, and nh_.
Referenced by configure().

      
  | 
  private | 
Definition at line 145 of file undo_path_global_planner.cpp.
References costmap_ros_, markersPub_, and nh_.
Referenced by createPlan().

      
  | 
  private | 
stored but almost not used
Definition at line 88 of file undo_path_global_planner.hpp.
Referenced by clearGoalMarker(), configure(), createDefaultUndoPathPlan(), createPlan(), and publishGoalMarker().
      
  | 
  private | 
Definition at line 79 of file undo_path_global_planner.hpp.
Referenced by configure().
      
  | 
  private | 
Definition at line 85 of file undo_path_global_planner.hpp.
Referenced by createDefaultUndoPathPlan(), createPlan(), and onForwardTrailMsg().
      
  | 
  private | 
Definition at line 83 of file undo_path_global_planner.hpp.
Referenced by activate(), clearGoalMarker(), configure(), deactivate(), and publishGoalMarker().
      
  | 
  private | 
Definition at line 106 of file undo_path_global_planner.hpp.
Referenced by configure().
      
  | 
  private | 
Definition at line 78 of file undo_path_global_planner.hpp.
Referenced by activate(), clearGoalMarker(), configure(), createDefaultUndoPathPlan(), createPlan(), deactivate(), onForwardTrailMsg(), publishGoalMarker(), and ~UndoPathGlobalPlanner().
      
  | 
  private | 
Definition at line 81 of file undo_path_global_planner.hpp.
Referenced by activate(), configure(), createPlan(), deactivate(), and ~UndoPathGlobalPlanner().
      
  | 
  private | 
Definition at line 102 of file undo_path_global_planner.hpp.
      
  | 
  private | 
Definition at line 100 of file undo_path_global_planner.hpp.
Referenced by UndoPathGlobalPlanner().
      
  | 
  private | 
Definition at line 108 of file undo_path_global_planner.hpp.
Referenced by configure(), createDefaultUndoPathPlan(), and createPlan().
      
  | 
  private | 
Definition at line 104 of file undo_path_global_planner.hpp.
Referenced by configure(), createDefaultUndoPathPlan(), createPlan(), and UndoPathGlobalPlanner().