Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Types | Public Member Functions | List of all members
nav2_system_tests::PlannerTester Class Reference
Inheritance diagram for nav2_system_tests::PlannerTester:
Inheritance graph
[legend]
Collaboration diagram for nav2_system_tests::PlannerTester:
Collaboration graph
[legend]

Public Types

using ComputePathToPoseCommand = geometry_msgs::msg::PoseStamped
 
using ComputePathToPoseResult = nav_msgs::msg::Path
 
- 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

void activate ()
 
void deactivate ()
 
void loadDefaultMap ()
 
void loadSimpleCostmap (const nav2_util::TestCostmap &testCostmapType)
 
bool defaultPlannerTest (ComputePathToPoseResult &path, const double deviation_tolerance=1.0)
 
bool defaultPlannerRandomTests (const unsigned int number_tests, const float acceptable_fail_ratio)
 
bool isPathValid (nav_msgs::msg::Path &path, unsigned int max_cost, bool consider_unknown_as_obstacle)
 
- 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.
 

Additional Inherited Members

- Protected Member Functions inherited from nav2::LifecycleNode
void printLifecycleNodeNotification ()
 Print notifications for lifecycle node.
 
void register_rcl_preshutdown_callback ()
 
void runCleanups ()
 
- 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

Definition at line 129 of file planner_tester.hpp.


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