Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
nav2_smoother::SmootherServer Class Reference

This class hosts variety of plugins of different algorithms to smooth or refine a path from the exposed SmoothPath action server. More...

#include <nav2_smoother/include/nav2_smoother/nav2_smoother.hpp>

Inheritance diagram for nav2_smoother::SmootherServer:
Inheritance graph
[legend]
Collaboration diagram for nav2_smoother::SmootherServer:
Collaboration graph
[legend]

Public Types

using SmootherMap = std::unordered_map< std::string, nav2_core::Smoother::Ptr >
 
- Public Types inherited from nav2::LifecycleNode
using SharedPtr = std::shared_ptr< nav2::LifecycleNode >
 
using WeakPtr = std::weak_ptr< nav2::LifecycleNode >
 
using SharedConstPointer = std::shared_ptr< const nav2::LifecycleNode >
 

Public Member Functions

 SmootherServer (const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A constructor for nav2_smoother::SmootherServer. More...
 
 ~SmootherServer ()
 Destructor for nav2_smoother::SmootherServer.
 
- Public Member Functions inherited from nav2::LifecycleNode
 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 &parameter_name, const ParamType &default_value, const ParameterDescriptor &parameter_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.
 

Protected Types

using Action = nav2_msgs::action::SmoothPath
 
using ActionResult = Action::Result
 
using ActionServer = nav2::SimpleActionServer< Action >
 

Protected Member Functions

nav2::CallbackReturn on_configure (const rclcpp_lifecycle::State &state) override
 Configures smoother parameters and member variables. More...
 
bool loadSmootherPlugins ()
 Loads smoother plugins from parameter file. More...
 
nav2::CallbackReturn on_activate (const rclcpp_lifecycle::State &state) override
 Activates member variables. More...
 
nav2::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &state) override
 Deactivates member variables. More...
 
nav2::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &state) override
 Calls clean up states and resets member variables. More...
 
nav2::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &state) override
 Called when in Shutdown state. More...
 
void smoothPlan ()
 SmoothPath action server callback. Handles action server updates and spins server until goal is reached. More...
 
bool findSmootherId (const std::string &c_name, std::string &name)
 Find the valid smoother ID name for the given request. More...
 
bool validate (const nav_msgs::msg::Path &path)
 Validate that the path contains a meaningful path for smoothing. More...
 
- Protected Member Functions inherited from nav2::LifecycleNode
void printLifecycleNodeNotification ()
 Print notifications for lifecycle node.
 
void register_rcl_preshutdown_callback ()
 
void runCleanups ()
 

Protected Attributes

ActionServer::SharedPtr action_server_
 
std::shared_ptr< tf2_ros::Buffer > tf_
 
std::shared_ptr< tf2_ros::TransformListener > transform_listener_
 
nav2::Publisher< nav_msgs::msg::Path >::SharedPtr plan_publisher_
 
pluginlib::ClassLoader< nav2_core::Smootherlp_loader_
 
SmootherMap smoothers_
 
std::vector< std::string > default_ids_
 
std::vector< std::string > default_types_
 
std::vector< std::string > smoother_ids_
 
std::vector< std::string > smoother_types_
 
std::string smoother_ids_concat_
 
std::string current_smoother_
 
std::shared_ptr< nav2_costmap_2d::CostmapSubscribercostmap_sub_
 
std::shared_ptr< nav2_costmap_2d::FootprintSubscriberfootprint_sub_
 
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionCheckercollision_checker_
 
- Protected Attributes inherited from nav2::LifecycleNode
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_
 

Detailed Description

This class hosts variety of plugins of different algorithms to smooth or refine a path from the exposed SmoothPath action server.

Definition at line 45 of file nav2_smoother.hpp.

Constructor & Destructor Documentation

◆ SmootherServer()

nav2_smoother::SmootherServer::SmootherServer ( const rclcpp::NodeOptions &  options = rclcpp::NodeOptions())
explicit

A constructor for nav2_smoother::SmootherServer.

Parameters
optionsAdditional options to control creation of the node.

Definition at line 33 of file nav2_smoother.cpp.

Member Function Documentation

◆ findSmootherId()

bool nav2_smoother::SmootherServer::findSmootherId ( const std::string &  c_name,
std::string &  name 
)
protected

Find the valid smoother ID name for the given request.

Parameters
c_nameThe requested smoother name
nameReference to the name to use for control if any valid available
Returns
bool Whether it found a valid smoother to use

Definition at line 222 of file nav2_smoother.cpp.

Referenced by smoothPlan().

Here is the caller graph for this function:

◆ loadSmootherPlugins()

bool nav2_smoother::SmootherServer::loadSmootherPlugins ( )
protected

Loads smoother plugins from parameter file.

Returns
bool if successfully loaded the plugins

Definition at line 117 of file nav2_smoother.cpp.

References nav2::LifecycleNode::shared_from_this().

Referenced by on_configure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ on_activate()

nav2::CallbackReturn nav2_smoother::SmootherServer::on_activate ( const rclcpp_lifecycle::State &  state)
overrideprotected

Activates member variables.

Activates smoother, costmap, velocity publisher and smooth path action server

Parameters
stateLifeCycle Node's state
Returns
Success or Failure

Definition at line 156 of file nav2_smoother.cpp.

References nav2::LifecycleNode::createBond().

Here is the call graph for this function:

◆ on_cleanup()

nav2::CallbackReturn nav2_smoother::SmootherServer::on_cleanup ( const rclcpp_lifecycle::State &  state)
overrideprotected

Calls clean up states and resets member variables.

Smoother and costmap clean up state is called, and resets rest of the variables

Parameters
stateLifeCycle Node's state
Returns
Success or Failure

Definition at line 192 of file nav2_smoother.cpp.

Referenced by on_configure().

Here is the caller graph for this function:

◆ on_configure()

nav2::CallbackReturn nav2_smoother::SmootherServer::on_configure ( const rclcpp_lifecycle::State &  state)
overrideprotected

Configures smoother parameters and member variables.

Configures smoother plugin and costmap; Initialize odom subscriber, velocity publisher and smooth path action server.

Parameters
stateLifeCycle Node's state
Returns
Success or Failure
Exceptions
pluginlib::PluginlibExceptionWhen failed to initialize smoother plugin

Definition at line 62 of file nav2_smoother.cpp.

References loadSmootherPlugins(), on_cleanup(), nav2::LifecycleNode::shared_from_this(), and smoothPlan().

Here is the call graph for this function:

◆ on_deactivate()

nav2::CallbackReturn nav2_smoother::SmootherServer::on_deactivate ( const rclcpp_lifecycle::State &  state)
overrideprotected

Deactivates member variables.

Deactivates smooth path action server, smoother, costmap and velocity publisher. Before calling deactivate state, velocity is being set to zero.

Parameters
stateLifeCycle Node's state
Returns
Success or Failure

Definition at line 174 of file nav2_smoother.cpp.

References nav2::LifecycleNode::destroyBond().

Here is the call graph for this function:

◆ on_shutdown()

nav2::CallbackReturn nav2_smoother::SmootherServer::on_shutdown ( const rclcpp_lifecycle::State &  state)
overrideprotected

Called when in Shutdown state.

Parameters
stateLifeCycle Node's state
Returns
Success or Failure

Definition at line 216 of file nav2_smoother.cpp.

◆ smoothPlan()

void nav2_smoother::SmootherServer::smoothPlan ( )
protected

SmoothPath action server callback. Handles action server updates and spins server until goal is reached.

Provides global path to smoother received from action client. Local section of the path is optimized using smoother.

Exceptions
nav2_core::PlannerException

Definition at line 251 of file nav2_smoother.cpp.

References findSmootherId(), and validate().

Referenced by on_configure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ validate()

bool nav2_smoother::SmootherServer::validate ( const nav_msgs::msg::Path &  path)
protected

Validate that the path contains a meaningful path for smoothing.

Parameters
pathcurrent path return bool if the path is valid

Definition at line 367 of file nav2_smoother.cpp.

Referenced by smoothPlan().

Here is the caller graph for this function:

The documentation for this class was generated from the following files: