Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
A nav2_behavior_tree::BtServiceNode class that removes goals that are in collision in on the global costmap wraps nav2_msgs::srv::GetCosts. More...
#include <nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.hpp>
Public Member Functions | |
RemoveInCollisionGoals (const std::string &service_node_name, const BT::NodeConfiguration &conf) | |
A constructor for nav2_behavior_tree::RemoveInCollisionGoals. More... | |
void | on_tick () override |
The main override required by a BT service. More... | |
BT::NodeStatus | on_completion (std::shared_ptr< nav2_msgs::srv::GetCosts::Response > response) override |
![]() | |
BtServiceNode (const std::string &service_node_name, const BT::NodeConfiguration &conf, const std::string &service_name="") | |
A nav2_behavior_tree::BtServiceNode constructor. More... | |
void | initialize () |
Function to read parameters and initialize class variables. | |
void | createROSInterfaces () |
Function to create ROS interfaces. | |
BT::NodeStatus | tick () override |
The main override required by a BT service. More... | |
void | halt () override |
The other (optional) override required by a BT service. | |
virtual BT::NodeStatus | on_completion (std::shared_ptr< typename ServiceT::Response >) |
Function to perform some user-defined operation upon successful completion of the service. Could put a value on the blackboard. More... | |
virtual BT::NodeStatus | check_future () |
Check the future and decide the status of BT. More... | |
virtual void | on_wait_for_result () |
Function to perform some user-defined operation after a timeout waiting for a result that hasn't been received yet. | |
Static Public Member Functions | |
static BT::PortsList | providedPorts () |
![]() | |
static BT::PortsList | providedBasicPorts (BT::PortsList addition) |
Any subclass of BtServiceNode that accepts parameters must provide a providedPorts method and call providedBasicPorts in it. More... | |
static BT::PortsList | providedPorts () |
Creates list of BT ports. More... | |
Additional Inherited Members | |
![]() | |
void | increment_recovery_count () |
Function to increment recovery count on blackboard if this node wraps a recovery. | |
![]() | |
std::string | service_name_ |
std::string | service_node_name_ |
nav2::ServiceClient< nav2_msgs::srv::GetCosts >::SharedPtr | service_client_ |
std::shared_ptr< typename ServiceT::Request > | request_ |
nav2::LifecycleNode::SharedPtr | node_ |
std::chrono::milliseconds | server_timeout_ |
std::chrono::milliseconds | max_timeout_ |
std::chrono::milliseconds | wait_for_service_timeout_ |
std::shared_future< typename ServiceT::Response::SharedPtr > | future_result_ |
bool | request_sent_ |
rclcpp::Time | sent_time_ |
bool | should_send_request_ |
A nav2_behavior_tree::BtServiceNode class that removes goals that are in collision in on the global costmap wraps nav2_msgs::srv::GetCosts.
Definition at line 37 of file remove_in_collision_goals_action.hpp.
nav2_behavior_tree::RemoveInCollisionGoals::RemoveInCollisionGoals | ( | const std::string & | service_node_name, |
const BT::NodeConfiguration & | conf | ||
) |
A constructor for nav2_behavior_tree::RemoveInCollisionGoals.
service_node_name | Service name this node creates a client for |
conf | BT node configuration |
Definition at line 28 of file remove_in_collision_goals_action.cpp.
|
overridevirtual |
The main override required by a BT service.
Reimplemented from nav2_behavior_tree::BtServiceNode< nav2_msgs::srv::GetCosts >.
Definition at line 36 of file remove_in_collision_goals_action.cpp.