SMACC2
|
#include <forward_global_planner.hpp>
Public Types | |
using | Ptr = std::shared_ptr< ForwardGlobalPlanner > |
Public Member Functions | |
ForwardGlobalPlanner () | |
virtual | ~ForwardGlobalPlanner () |
Virtual destructor. More... | |
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 |
virtual void | cleanup () |
Method to cleanup resources used on shutdown. More... | |
virtual void | activate () |
Method to active planner and any threads involved in execution. More... | |
virtual void | deactivate () |
Method to deactivate planner and any threads involved in execution. More... | |
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. More... | |
Private Attributes | |
rclcpp_lifecycle::LifecycleNode::SharedPtr | nh_ |
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path > > | planPub_ |
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > | costmap_ros_ |
stored but almost not used More... | |
double | skip_straight_motion_distance_ |
double | puresSpinningRadStep_ |
std::string | name_ |
double | transform_tolerance_ |
std::shared_ptr< tf2_ros::Buffer > | tf_ |
Definition at line 33 of file forward_global_planner.hpp.
using cl_nav2z::forward_global_planner::ForwardGlobalPlanner::Ptr = std::shared_ptr<ForwardGlobalPlanner> |
Definition at line 36 of file forward_global_planner.hpp.
cl_nav2z::forward_global_planner::ForwardGlobalPlanner::ForwardGlobalPlanner | ( | ) |
Definition at line 42 of file forward_global_planner.cpp.
References puresSpinningRadStep_, and skip_straight_motion_distance_.
|
virtual |
|
virtual |
Method to active planner and any threads involved in execution.
Definition at line 70 of file forward_global_planner.cpp.
References planPub_.
|
virtual |
Method to cleanup resources used on shutdown.
Definition at line 68 of file forward_global_planner.cpp.
|
override |
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 |
Definition at line 51 of file forward_global_planner.cpp.
References costmap_ros_, name_, nh_, planPub_, puresSpinningRadStep_, skip_straight_motion_distance_, tf_, and transform_tolerance_.
|
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 |
Definition at line 79 of file forward_global_planner.cpp.
References costmap_ros_, cl_nav2z::makePureSpinningSubPlan(), cl_nav2z::makePureStraightSubPlan(), nh_, planPub_, puresSpinningRadStep_, skip_straight_motion_distance_, tf_, and transform_tolerance_.
|
virtual |
Method to deactivate planner and any threads involved in execution.
Definition at line 72 of file forward_global_planner.cpp.
References planPub_.
|
private |
stored but almost not used
Definition at line 87 of file forward_global_planner.hpp.
Referenced by configure(), and createPlan().
|
private |
Definition at line 93 of file forward_global_planner.hpp.
Referenced by configure().
|
private |
Definition at line 82 of file forward_global_planner.hpp.
Referenced by configure(), and createPlan().
|
private |
Definition at line 84 of file forward_global_planner.hpp.
Referenced by activate(), configure(), createPlan(), and deactivate().
|
private |
Definition at line 91 of file forward_global_planner.hpp.
Referenced by configure(), createPlan(), and ForwardGlobalPlanner().
|
private |
Definition at line 89 of file forward_global_planner.hpp.
Referenced by configure(), createPlan(), and ForwardGlobalPlanner().
|
private |
Definition at line 97 of file forward_global_planner.hpp.
Referenced by configure(), and createPlan().
|
private |
Definition at line 95 of file forward_global_planner.hpp.
Referenced by configure(), and createPlan().