Class SmootherServer

Inheritance Relationships

Base Type

  • public nav2_util::LifecycleNode

Class Documentation

class SmootherServer : public nav2_util::LifecycleNode

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

Public Types

using SmootherMap = std::unordered_map<std::string, nav2_core::Smoother::Ptr>

Public Functions

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

A constructor for nav2_smoother::SmootherServer.

Parameters:

options – Additional options to control creation of the node.

~SmootherServer()

Destructor for nav2_smoother::SmootherServer.

Protected Types

using Action = nav2_msgs::action::SmoothPath
using ActionServer = nav2_util::SimpleActionServer<Action>

Protected Functions

nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override

Configures smoother parameters and member variables.

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

Parameters:

state – LifeCycle Node’s state

Throws:

pluginlib::PluginlibException – When failed to initialize smoother plugin

Returns:

Success or Failure

bool loadSmootherPlugins()

Loads smoother plugins from parameter file.

Returns:

bool if successfully loaded the plugins

nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override

Activates member variables.

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

Parameters:

state – LifeCycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override

Deactivates member variables.

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

Parameters:

state – LifeCycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override

Calls clean up states and resets member variables.

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

Parameters:

state – LifeCycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override

Called when in Shutdown state.

Parameters:

state – LifeCycle Node’s state

Returns:

Success or Failure

void smoothPlan()

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.

Throws:

nav2_core::PlannerException

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

Find the valid smoother ID name for the given request.

Parameters:
  • c_name – The requested smoother name

  • name – Reference to the name to use for control if any valid available

Returns:

bool Whether it found a valid smoother to use

Protected Attributes

std::unique_ptr<ActionServer> action_server_
std::shared_ptr<tf2_ros::Buffer> tf_
std::shared_ptr<tf2_ros::TransformListener> transform_listener_
rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr plan_publisher_
pluginlib::ClassLoader<nav2_core::Smoother> lp_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::CostmapSubscriber> costmap_sub_
std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_
std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_