Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
An server hosting a map of behavior plugins. More...
#include <nav2_behaviors/include/nav2_behaviors/behavior_server.hpp>
Public Member Functions | |
BehaviorServer (const rclcpp::NodeOptions &options=rclcpp::NodeOptions()) | |
A constructor for behavior_server::BehaviorServer. 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. | |
Protected Member Functions | |
bool | loadBehaviorPlugins () |
Loads behavior plugins from parameter file. More... | |
void | configureBehaviorPlugins () |
configures behavior plugins | |
void | setupResourcesForBehaviorPlugins () |
configures behavior plugins | |
nav2::CallbackReturn | on_configure (const rclcpp_lifecycle::State &state) override |
Configure lifecycle server. | |
nav2::CallbackReturn | on_activate (const rclcpp_lifecycle::State &state) override |
Activate lifecycle server. | |
nav2::CallbackReturn | on_deactivate (const rclcpp_lifecycle::State &state) override |
Deactivate lifecycle server. | |
nav2::CallbackReturn | on_cleanup (const rclcpp_lifecycle::State &state) override |
Cleanup lifecycle server. | |
nav2::CallbackReturn | on_shutdown (const rclcpp_lifecycle::State &state) override |
Shutdown lifecycle server. | |
![]() | |
void | printLifecycleNodeNotification () |
Print notifications for lifecycle node. | |
void | register_rcl_preshutdown_callback () |
void | runCleanups () |
Protected Attributes | |
std::shared_ptr< tf2_ros::Buffer > | tf_ |
std::shared_ptr< tf2_ros::TransformListener > | transform_listener_ |
pluginlib::ClassLoader< nav2_core::Behavior > | plugin_loader_ |
std::vector< pluginlib::UniquePtr< nav2_core::Behavior > > | behaviors_ |
std::vector< std::string > | default_ids_ |
std::vector< std::string > | default_types_ |
std::vector< std::string > | behavior_ids_ |
std::vector< std::string > | behavior_types_ |
std::unique_ptr< nav2_costmap_2d::CostmapSubscriber > | local_costmap_sub_ |
std::unique_ptr< nav2_costmap_2d::FootprintSubscriber > | local_footprint_sub_ |
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > | local_collision_checker_ |
std::unique_ptr< nav2_costmap_2d::CostmapSubscriber > | global_costmap_sub_ |
std::unique_ptr< nav2_costmap_2d::FootprintSubscriber > | global_footprint_sub_ |
std::shared_ptr< nav2_costmap_2d::CostmapTopicCollisionChecker > | global_collision_checker_ |
![]() | |
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_ |
Additional Inherited Members | |
![]() | |
using | SharedPtr = std::shared_ptr< nav2::LifecycleNode > |
using | WeakPtr = std::weak_ptr< nav2::LifecycleNode > |
using | SharedConstPointer = std::shared_ptr< const nav2::LifecycleNode > |
An server hosting a map of behavior plugins.
Definition at line 38 of file behavior_server.hpp.
|
explicit |
A constructor for behavior_server::BehaviorServer.
options | Additional options to control creation of the node. |
Definition at line 25 of file behavior_server.cpp.
|
protected |
Loads behavior plugins from parameter file.
Definition at line 104 of file behavior_server.cpp.
References nav2::LifecycleNode::shared_from_this().
Referenced by on_configure().