Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
Public Member Functions | |
NavfnPlanner () | |
constructor | |
~NavfnPlanner () | |
destructor | |
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) override |
Configuring plugin. More... | |
void | cleanup () override |
Cleanup lifecycle node. | |
void | activate () override |
Activate lifecycle node. | |
void | deactivate () override |
Deactivate lifecycle node. | |
nav_msgs::msg::Path | createPlan (const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal) override |
Creating a plan from start and goal poses. More... | |
![]() | |
virtual | ~GlobalPlanner () |
Virtual destructor. | |
Protected Member Functions | |
bool | makePlan (const geometry_msgs::msg::Pose &start, const geometry_msgs::msg::Pose &goal, double tolerance, nav_msgs::msg::Path &plan) |
Compute a plan given start and goal poses, provided in global world frame. More... | |
bool | computePotential (const geometry_msgs::msg::Point &world_point) |
Compute the navigation function given a seed point in the world to start from. More... | |
bool | getPlanFromPotential (const geometry_msgs::msg::Pose &goal, nav_msgs::msg::Path &plan) |
Compute a plan to a goal from a potential - must call computePotential first. More... | |
void | smoothApproachToGoal (const geometry_msgs::msg::Pose &goal, nav_msgs::msg::Path &plan) |
Remove artifacts at the end of the path - originated from planning on a discretized world. More... | |
double | getPointPotential (const geometry_msgs::msg::Point &world_point) |
Compute the potential, or navigation cost, at a given point in the world must call computePotential first. More... | |
double | squared_distance (const geometry_msgs::msg::Pose &p1, const geometry_msgs::msg::Pose &p2) |
Compute the squared distance between two points. More... | |
bool | worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my) |
Transform a point from world to map frame. More... | |
void | mapToWorld (double mx, double my, double &wx, double &wy) |
Transform a point from map to world frame. More... | |
void | clearRobotCell (unsigned int mx, unsigned int my) |
Set the corresponding cell cost to be free space. More... | |
bool | isPlannerOutOfDate () |
Determine if a new planner object should be made. More... | |
rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
Callback executed when a paramter change is detected. More... | |
Protected Attributes | |
std::unique_ptr< NavFn > | planner_ |
std::shared_ptr< tf2_ros::Buffer > | tf_ |
rclcpp::Clock::SharedPtr | clock_ |
rclcpp::Logger | logger_ {rclcpp::get_logger("NavfnPlanner")} |
nav2_costmap_2d::Costmap2D * | costmap_ |
std::string | global_frame_ |
std::string | name_ |
bool | allow_unknown_ |
bool | use_final_approach_orientation_ |
double | tolerance_ |
bool | use_astar_ |
rclcpp_lifecycle::LifecycleNode::WeakPtr | node_ |
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | dyn_params_handler_ |
Additional Inherited Members | |
![]() | |
using | Ptr = std::shared_ptr< GlobalPlanner > |
Definition at line 38 of file navfn_planner.hpp.
|
protected |
Set the corresponding cell cost to be free space.
mx | int of map X coordinate |
my | int of map Y coordinate |
Definition at line 517 of file navfn_planner.cpp.
References nav2_costmap_2d::Costmap2D::setCost().
Referenced by makePlan().
|
protected |
Compute the navigation function given a seed point in the world to start from.
world_point | Point in world coordinate frame |
|
overridevirtual |
Configuring plugin.
parent | Lifecycle node pointer |
name | Name of plugin map |
tf | Shared ptr of TF2 buffer |
costmap_ros | Costmap2DROS object |
Implements nav2_core::GlobalPlanner.
Definition at line 63 of file navfn_planner.cpp.
References nav2_costmap_2d::Costmap2D::getSizeInCellsX(), and nav2_costmap_2d::Costmap2D::getSizeInCellsY().
|
overridevirtual |
Creating a plan from start and goal poses.
start | Start pose |
goal | Goal pose |
Implements nav2_core::GlobalPlanner.
Definition at line 130 of file navfn_planner.cpp.
References nav2_costmap_2d::Costmap2D::getCost(), nav2_costmap_2d::Costmap2D::getSizeInCellsX(), nav2_costmap_2d::Costmap2D::getSizeInCellsY(), isPlannerOutOfDate(), makePlan(), and nav2_costmap_2d::Costmap2D::worldToMap().
|
protected |
Callback executed when a paramter change is detected.
parameters | list of changed parameters |
Definition at line 525 of file navfn_planner.cpp.
Referenced by activate().
|
protected |
Compute a plan to a goal from a potential - must call computePotential first.
goal | Goal pose |
plan | Path to be computed |
Definition at line 371 of file navfn_planner.cpp.
References nav2_costmap_2d::Costmap2D::getSizeInCellsX(), nav2_costmap_2d::Costmap2D::getSizeInCellsY(), mapToWorld(), and worldToMap().
Referenced by makePlan().
|
protected |
Compute the potential, or navigation cost, at a given point in the world must call computePotential first.
world_point | Point in world coordinate frame |
Definition at line 437 of file navfn_planner.cpp.
References worldToMap().
Referenced by makePlan().
|
protected |
Determine if a new planner object should be made.
Definition at line 191 of file navfn_planner.cpp.
References nav2_costmap_2d::Costmap2D::getSizeInCellsX(), and nav2_costmap_2d::Costmap2D::getSizeInCellsY().
Referenced by createPlan().
|
protected |
Compute a plan given start and goal poses, provided in global world frame.
start | Start pose |
goal | Goal pose |
tolerance | Relaxation constraint in x and y |
plan | Path to be computed |
Definition at line 203 of file navfn_planner.cpp.
References clearRobotCell(), nav2_costmap_2d::Costmap2D::getCharMap(), getPlanFromPotential(), getPointPotential(), nav2_costmap_2d::Costmap2D::getResolution(), nav2_costmap_2d::Costmap2D::getSizeInCellsX(), nav2_costmap_2d::Costmap2D::getSizeInCellsY(), smoothApproachToGoal(), squared_distance(), and worldToMap().
Referenced by createPlan().
|
protected |
Transform a point from map to world frame.
mx | double of map X coordinate |
my | double of map Y coordinate |
wx | double of world X coordinate |
wy | double of world Y coordinate |
Definition at line 510 of file navfn_planner.cpp.
References nav2_costmap_2d::Costmap2D::getOriginX(), nav2_costmap_2d::Costmap2D::getOriginY(), and nav2_costmap_2d::Costmap2D::getResolution().
Referenced by getPlanFromPotential().
|
protected |
Remove artifacts at the end of the path - originated from planning on a discretized world.
goal | Goal pose |
plan | Computed path |
Definition at line 347 of file navfn_planner.cpp.
References squared_distance().
Referenced by makePlan().
|
inlineprotected |
Compute the squared distance between two points.
p1 | Point 1 |
p2 | Point 2 |
Definition at line 149 of file navfn_planner.hpp.
Referenced by makePlan(), and smoothApproachToGoal().
|
protected |
Transform a point from world to map frame.
wx | double of world X coordinate |
wy | double of world Y coordinate |
mx | int of map X coordinate |
my | int of map Y coordinate |
Definition at line 486 of file navfn_planner.cpp.
References nav2_costmap_2d::Costmap2D::getOriginX(), nav2_costmap_2d::Costmap2D::getOriginY(), nav2_costmap_2d::Costmap2D::getResolution(), nav2_costmap_2d::Costmap2D::getSizeInCellsX(), and nav2_costmap_2d::Costmap2D::getSizeInCellsY().
Referenced by getPlanFromPotential(), getPointPotential(), and makePlan().