Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
Public Member Functions | |
void | printCostmap () |
void | setCostmap (nav2_util::Costmap *costmap) |
bool | createPath (const geometry_msgs::msg::PoseStamped &goal, nav_msgs::msg::Path &path) |
void | onCleanup (const rclcpp_lifecycle::State &state) |
void | onActivate (const rclcpp_lifecycle::State &state) |
void | onDeactivate (const rclcpp_lifecycle::State &state) |
void | onConfigure (const rclcpp_lifecycle::State &state) |
![]() | |
PlannerServer (const rclcpp::NodeOptions &options=rclcpp::NodeOptions()) | |
A constructor for nav2_planner::PlannerServer. More... | |
~PlannerServer () | |
A destructor for nav2_planner::PlannerServer. | |
nav_msgs::msg::Path | getPlan (const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, const std::string &planner_id, std::function< bool()> cancel_checker) |
Method to get plan from the desired plugin. More... | |
![]() | |
LifecycleNode (const std::string &node_name, const std::string &ns, const rclcpp::NodeOptions &options=rclcpp::NodeOptions()) | |
A lifecycle node constructor. More... | |
LifecycleNode (const std::string &node_name, const rclcpp::NodeOptions &options=rclcpp::NodeOptions()) | |
A lifecycle node constructor with no namespace. More... | |
template<typename ParamType > | |
ParamType | declare_or_get_parameter (const std::string ¶meter_name, const ParamType &default_value, const ParameterDescriptor ¶meter_descriptor=ParameterDescriptor()) |
Declares or gets a parameter. If the parameter is already declared, returns its value; otherwise declares it and returns the default value. More... | |
template<typename MessageT , typename CallbackT > | |
nav2::Subscription< MessageT >::SharedPtr | create_subscription (const std::string &topic_name, CallbackT &&callback, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS(), const rclcpp::CallbackGroup::SharedPtr &callback_group=nullptr) |
Create a subscription to a topic using Nav2 QoS profiles and SubscriptionOptions. More... | |
template<typename MessageT > | |
nav2::Publisher< MessageT >::SharedPtr | create_publisher (const std::string &topic_name, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS(), const rclcpp::CallbackGroup::SharedPtr &callback_group=nullptr) |
Create a publisher to a topic using Nav2 QoS profiles and PublisherOptions. More... | |
template<typename ServiceT > | |
nav2::ServiceClient< ServiceT >::SharedPtr | create_client (const std::string &service_name, bool use_internal_executor=false) |
Create a ServiceClient to interface with a service. More... | |
template<typename ServiceT > | |
nav2::ServiceServer< ServiceT >::SharedPtr | create_service (const std::string &service_name, typename nav2::ServiceServer< ServiceT >::CallbackType cb, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr) |
Create a ServiceServer to host with a service. More... | |
template<typename ActionT > | |
nav2::SimpleActionServer< ActionT >::SharedPtr | create_action_server (const std::string &action_name, typename nav2::SimpleActionServer< ActionT >::ExecuteCallback execute_callback, typename nav2::SimpleActionServer< ActionT >::CompletionCallback compl_cb=nullptr, std::chrono::milliseconds server_timeout=std::chrono::milliseconds(500), bool spin_thread=false, const bool realtime=false) |
Create a SimpleActionServer to host with an action. More... | |
template<typename ActionT > | |
nav2::ActionClient< ActionT >::SharedPtr | create_action_client (const std::string &action_name, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr) |
Create a ActionClient to call an action using. More... | |
nav2::LifecycleNode::SharedPtr | shared_from_this () |
Get a shared pointer of this. | |
nav2::LifecycleNode::WeakPtr | weak_from_this () |
Get a shared pointer of this. | |
nav2::CallbackReturn | on_error (const rclcpp_lifecycle::State &) |
Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 node state machine. More... | |
void | autostart () |
Automatically configure and active the node. | |
virtual void | on_rcl_preshutdown () |
Perform preshutdown activities before our Context is shutdown. Note that this is related to our Context's shutdown sequence, not the lifecycle node state machine. | |
void | createBond () |
Create bond connection to lifecycle manager. | |
void | destroyBond () |
Destroy bond connection to lifecycle manager. | |
Additional Inherited Members | |
![]() | |
using | PlannerMap = std::unordered_map< std::string, nav2_core::GlobalPlanner::Ptr > |
![]() | |
using | SharedPtr = std::shared_ptr< nav2::LifecycleNode > |
using | WeakPtr = std::weak_ptr< nav2::LifecycleNode > |
using | SharedConstPointer = std::shared_ptr< const nav2::LifecycleNode > |
![]() | |
using | ActionToPose = nav2_msgs::action::ComputePathToPose |
using | ActionToPoseResult = ActionToPose::Result |
using | ActionThroughPoses = nav2_msgs::action::ComputePathThroughPoses |
using | ActionThroughPosesResult = ActionThroughPoses::Result |
using | ActionServerToPose = nav2::SimpleActionServer< ActionToPose > |
using | ActionServerThroughPoses = nav2::SimpleActionServer< ActionThroughPoses > |
![]() | |
nav2::CallbackReturn | on_configure (const rclcpp_lifecycle::State &state) override |
Configure member variables and initializes planner. More... | |
nav2::CallbackReturn | on_activate (const rclcpp_lifecycle::State &state) override |
Activate member variables. More... | |
nav2::CallbackReturn | on_deactivate (const rclcpp_lifecycle::State &state) override |
Deactivate member variables. More... | |
nav2::CallbackReturn | on_cleanup (const rclcpp_lifecycle::State &state) override |
Reset member variables. More... | |
nav2::CallbackReturn | on_shutdown (const rclcpp_lifecycle::State &state) override |
Called when in shutdown state. More... | |
template<typename T > | |
bool | isServerInactive (typename nav2::SimpleActionServer< T >::SharedPtr &action_server) |
Check if an action server is valid / active. More... | |
template<typename T > | |
bool | isCancelRequested (typename nav2::SimpleActionServer< T >::SharedPtr &action_server) |
Check if an action server has a cancellation request pending. More... | |
void | waitForCostmap () |
Wait for costmap to be valid with updated sensor data or repopulate after a clearing recovery. Blocks until true without timeout. | |
template<typename T > | |
void | getPreemptedGoalIfRequested (typename nav2::SimpleActionServer< T >::SharedPtr &action_server, typename std::shared_ptr< const typename T::Goal > goal) |
Check if an action server has a preemption request and replaces the goal with the new preemption goal. More... | |
template<typename T > | |
bool | getStartPose (typename std::shared_ptr< const typename T::Goal > goal, geometry_msgs::msg::PoseStamped &start) |
Get the starting pose from costmap or message, if valid. More... | |
bool | transformPosesToGlobalFrame (geometry_msgs::msg::PoseStamped &curr_start, geometry_msgs::msg::PoseStamped &curr_goal) |
Transform start and goal poses into the costmap global frame for path planning plugins to utilize. More... | |
template<typename T > | |
bool | validatePath (const geometry_msgs::msg::PoseStamped &curr_goal, const nav_msgs::msg::Path &path, const std::string &planner_id) |
Validate that the path contains a meaningful path. More... | |
void | computePlan () |
The action server callback which calls planner to get the path ComputePathToPose. | |
void | computePlanThroughPoses () |
The action server callback which calls planner to get the path ComputePathThroughPoses. | |
void | isPathValid (const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav2_msgs::srv::IsPathValid::Request > request, std::shared_ptr< nav2_msgs::srv::IsPathValid::Response > response) |
The service callback to determine if the path is still valid. More... | |
void | publishPlan (const nav_msgs::msg::Path &path) |
Publish a path for visualization purposes. More... | |
void | exceptionWarning (const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, const std::string &planner_id, const std::exception &ex, std::string &msg) |
rcl_interfaces::msg::SetParametersResult | dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters) |
Callback executed when a parameter change is detected. More... | |
![]() | |
void | printLifecycleNodeNotification () |
Print notifications for lifecycle node. | |
void | register_rcl_preshutdown_callback () |
void | runCleanups () |
![]() | |
ActionServerToPose::SharedPtr | action_server_pose_ |
ActionServerThroughPoses::SharedPtr | action_server_poses_ |
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | dyn_params_handler_ |
std::mutex | dynamic_params_lock_ |
PlannerMap | planners_ |
pluginlib::ClassLoader< nav2_core::GlobalPlanner > | gp_loader_ |
std::vector< std::string > | default_ids_ |
std::vector< std::string > | default_types_ |
std::vector< std::string > | planner_ids_ |
std::vector< std::string > | planner_types_ |
double | max_planner_duration_ |
rclcpp::Duration | costmap_update_timeout_ |
std::string | planner_ids_concat_ |
std::shared_ptr< tf2_ros::Buffer > | tf_ |
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > | costmap_ros_ |
std::unique_ptr< nav2::NodeThread > | costmap_thread_ |
nav2_costmap_2d::Costmap2D * | costmap_ |
std::unique_ptr< nav2_costmap_2d::FootprintCollisionChecker< nav2_costmap_2d::Costmap2D * > > | collision_checker_ |
nav2::Publisher< nav_msgs::msg::Path >::SharedPtr | plan_publisher_ |
nav2::ServiceServer< nav2_msgs::srv::IsPathValid >::SharedPtr | is_path_valid_service_ |
![]() | |
std::unique_ptr< rclcpp::PreShutdownCallbackHandle > | rcl_preshutdown_cb_handle_ {nullptr} |
std::shared_ptr< bond::Bond > | bond_ {nullptr} |
double | bond_heartbeat_period {0.1} |
rclcpp::TimerBase::SharedPtr | autostart_timer_ |
Definition at line 40 of file planner_tester.hpp.