Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_waypoint_follower::WaypointFollower Class Reference

An action server that uses behavior tree for navigating a robot to its goal position. More...

#include <nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp>

Inheritance diagram for nav2_waypoint_follower::WaypointFollower:
Inheritance graph
[legend]
Collaboration diagram for nav2_waypoint_follower::WaypointFollower:
Collaboration graph
[legend]

Public Types

using ActionT = nav2_msgs::action::FollowWaypoints
 
using ClientT = nav2_msgs::action::NavigateToPose
 
using ActionServer = nav2_util::SimpleActionServer< ActionT >
 
using ActionClient = rclcpp_action::Client< ClientT >
 
using ActionTGPS = nav2_msgs::action::FollowGPSWaypoints
 
using ActionServerGPS = nav2_util::SimpleActionServer< ActionTGPS >
 

Public Member Functions

 WaypointFollower (const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A constructor for nav2_waypoint_follower::WaypointFollower class. More...
 
 ~WaypointFollower ()
 A destructor for nav2_waypoint_follower::WaypointFollower class.
 
- Public Member Functions inherited from nav2_util::LifecycleNode
 LifecycleNode (const std::string &node_name, const std::string &ns="", const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A lifecycle node constructor. More...
 
void add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
 Declare a parameter that has no integer or floating point range constraints. More...
 
void add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const floating_point_range fp_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
 Declare a parameter that has a floating point range constraint. More...
 
void add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const integer_range int_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
 Declare a parameter that has an integer range constraint. More...
 
std::shared_ptr< nav2_util::LifecycleNodeshared_from_this ()
 Get a shared pointer of this.
 
nav2_util::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

nav2_util::CallbackReturn on_configure (const rclcpp_lifecycle::State &state) override
 Configures member variables. More...
 
nav2_util::CallbackReturn on_activate (const rclcpp_lifecycle::State &state) override
 Activates action server. More...
 
nav2_util::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &state) override
 Deactivates action server. More...
 
nav2_util::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &state) override
 Resets member variables. More...
 
nav2_util::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &state) override
 Called when in shutdown state. More...
 
template<typename T , typename V , typename Z >
void followWaypointsHandler (const T &action_server, const V &feedback, const Z &result)
 Templated function to perform internal logic behind waypoint following, Both GPS and non GPS waypoint following callbacks makes use of this function when a client asked to do so. Callbacks fills in appropriate types for the templated types, see followWaypointCallback functions for details. More...
 
void followWaypointsCallback ()
 Action server callbacks.
 
void followGPSWaypointsCallback ()
 send robot through each of GPS point , which are converted to map frame first then using a client to FollowWaypoints action. More...
 
void resultCallback (const rclcpp_action::ClientGoalHandle< ClientT >::WrappedResult &result)
 Action client result callback. More...
 
void goalResponseCallback (const rclcpp_action::ClientGoalHandle< ClientT >::SharedPtr &goal)
 Action client goal response callback. More...
 
std::vector< geometry_msgs::msg::PoseStamped > convertGPSPosesToMapPoses (const std::vector< geographic_msgs::msg::GeoPose > &gps_poses)
 given some gps_poses, converts them to map frame using robot_localization's service fromLL. Constructs a vector of stamped poses in map frame and returns them. More...
 
template<typename T >
std::vector< geometry_msgs::msg::PoseStamped > getLatestGoalPoses (const T &action_server)
 get the latest poses on the action server goal. If they are GPS poses, convert them to the global cartesian frame using /fromLL robot localization server More...
 
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters)
 Callback executed when a parameter change is detected. More...
 
- Protected Member Functions inherited from nav2_util::LifecycleNode
void printLifecycleNodeNotification ()
 Print notifications for lifecycle node.
 
void register_rcl_preshutdown_callback ()
 
void runCleanups ()
 

Protected Attributes

std::vector< int > failed_ids_
 
std::string global_frame_id_ {"map"}
 
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
 
std::unique_ptr< ActionServerxyz_action_server_
 
ActionClient::SharedPtr nav_to_pose_client_
 
rclcpp::CallbackGroup::SharedPtr callback_group_
 
rclcpp::executors::SingleThreadedExecutor callback_group_executor_
 
std::shared_future< rclcpp_action::ClientGoalHandle< ClientT >::SharedPtr > future_goal_handle_
 
std::unique_ptr< ActionServerGPSgps_action_server_
 
std::unique_ptr< nav2_util::ServiceClient< robot_localization::srv::FromLL, std::shared_ptr< nav2_util::LifecycleNode > > > from_ll_to_map_client_
 
bool stop_on_failure_
 
int loop_rate_
 
GoalStatus current_goal_status_
 
pluginlib::ClassLoader< nav2_core::WaypointTaskExecutorwaypoint_task_executor_loader_
 
pluginlib::UniquePtr< nav2_core::WaypointTaskExecutorwaypoint_task_executor_
 
std::string waypoint_task_executor_id_
 
std::string waypoint_task_executor_type_
 
- Protected Attributes inherited from nav2_util::LifecycleNode
std::unique_ptr< rclcpp::PreShutdownCallbackHandle > rcl_preshutdown_cb_handle_ {nullptr}
 
std::shared_ptr< bond::Bond > bond_ {nullptr}
 
double bond_heartbeat_period
 
rclcpp::TimerBase::SharedPtr autostart_timer_
 

Detailed Description

An action server that uses behavior tree for navigating a robot to its goal position.

Definition at line 67 of file waypoint_follower.hpp.

Constructor & Destructor Documentation

◆ WaypointFollower()

nav2_waypoint_follower::WaypointFollower::WaypointFollower ( const rclcpp::NodeOptions &  options = rclcpp::NodeOptions())
explicit

A constructor for nav2_waypoint_follower::WaypointFollower class.

Parameters
optionsAdditional options to control creation of the node.

Definition at line 30 of file waypoint_follower.cpp.

Member Function Documentation

◆ convertGPSPosesToMapPoses()

std::vector< geometry_msgs::msg::PoseStamped > nav2_waypoint_follower::WaypointFollower::convertGPSPosesToMapPoses ( const std::vector< geographic_msgs::msg::GeoPose > &  gps_poses)
protected

given some gps_poses, converts them to map frame using robot_localization's service fromLL. Constructs a vector of stamped poses in map frame and returns them.

Parameters
gps_poses,fromthe action server
Returns
std::vector<geometry_msgs::msg::PoseStamped>

Definition at line 493 of file waypoint_follower.cpp.

Referenced by getLatestGoalPoses().

Here is the caller graph for this function:

◆ dynamicParametersCallback()

rcl_interfaces::msg::SetParametersResult nav2_waypoint_follower::WaypointFollower::dynamicParametersCallback ( std::vector< rclcpp::Parameter >  parameters)
protected

Callback executed when a parameter change is detected.

Parameters
eventParameterEvent message

Definition at line 465 of file waypoint_follower.cpp.

Referenced by on_activate().

Here is the caller graph for this function:

◆ followGPSWaypointsCallback()

void nav2_waypoint_follower::WaypointFollower::followGPSWaypointsCallback ( )
protected

send robot through each of GPS point , which are converted to map frame first then using a client to FollowWaypoints action.

Parameters
waypoints,acquiredfrom action client

Definition at line 406 of file waypoint_follower.cpp.

Referenced by on_configure().

Here is the caller graph for this function:

◆ followWaypointsHandler()

template<typename T , typename V , typename Z >
void nav2_waypoint_follower::WaypointFollower::followWaypointsHandler ( const T &  action_server,
const V &  feedback,
const Z &  result 
)
protected

Templated function to perform internal logic behind waypoint following, Both GPS and non GPS waypoint following callbacks makes use of this function when a client asked to do so. Callbacks fills in appropriate types for the templated types, see followWaypointCallback functions for details.

Template Parameters
Taction_server
Vfeedback
Zresult
Parameters
action_server
poses
feedback
result

Definition at line 206 of file waypoint_follower.cpp.

References goalResponseCallback(), and resultCallback().

Here is the call graph for this function:

◆ getLatestGoalPoses()

template<typename T >
std::vector< geometry_msgs::msg::PoseStamped > nav2_waypoint_follower::WaypointFollower::getLatestGoalPoses ( const T &  action_server)
protected

get the latest poses on the action server goal. If they are GPS poses, convert them to the global cartesian frame using /fromLL robot localization server

Parameters
action_server,towhich the goal was sent
Returns
std::vector<geometry_msgs::msg::PoseStamped>

Definition at line 182 of file waypoint_follower.cpp.

References convertGPSPosesToMapPoses().

Here is the call graph for this function:

◆ goalResponseCallback()

void nav2_waypoint_follower::WaypointFollower::goalResponseCallback ( const rclcpp_action::ClientGoalHandle< ClientT >::SharedPtr &  goal)
protected

Action client goal response callback.

Parameters
goalResponse of action server updated asynchronously

Definition at line 452 of file waypoint_follower.cpp.

Referenced by followWaypointsHandler().

Here is the caller graph for this function:

◆ on_activate()

nav2_util::CallbackReturn nav2_waypoint_follower::WaypointFollower::on_activate ( const rclcpp_lifecycle::State &  state)
overrideprotected

Activates action server.

Parameters
stateReference to LifeCycle node state
Returns
SUCCESS or FAILURE

Definition at line 128 of file waypoint_follower.cpp.

References nav2_util::LifecycleNode::createBond(), dynamicParametersCallback(), and nav2_util::LifecycleNode::shared_from_this().

Here is the call graph for this function:

◆ on_cleanup()

nav2_util::CallbackReturn nav2_waypoint_follower::WaypointFollower::on_cleanup ( const rclcpp_lifecycle::State &  state)
overrideprotected

Resets member variables.

Parameters
stateReference to LifeCycle node state
Returns
SUCCESS or FAILURE

Definition at line 162 of file waypoint_follower.cpp.

Referenced by on_configure().

Here is the caller graph for this function:

◆ on_configure()

nav2_util::CallbackReturn nav2_waypoint_follower::WaypointFollower::on_configure ( const rclcpp_lifecycle::State &  state)
overrideprotected

Configures member variables.

Initializes action server for "follow_waypoints"

Parameters
stateReference to LifeCycle node state
Returns
SUCCESS or FAILURE

Definition at line 55 of file waypoint_follower.cpp.

References followGPSWaypointsCallback(), followWaypointsCallback(), on_cleanup(), and nav2_util::LifecycleNode::shared_from_this().

Here is the call graph for this function:

◆ on_deactivate()

nav2_util::CallbackReturn nav2_waypoint_follower::WaypointFollower::on_deactivate ( const rclcpp_lifecycle::State &  state)
overrideprotected

Deactivates action server.

Parameters
stateReference to LifeCycle node state
Returns
SUCCESS or FAILURE

Definition at line 147 of file waypoint_follower.cpp.

References nav2_util::LifecycleNode::destroyBond().

Here is the call graph for this function:

◆ on_shutdown()

nav2_util::CallbackReturn nav2_waypoint_follower::WaypointFollower::on_shutdown ( const rclcpp_lifecycle::State &  state)
overrideprotected

Called when in shutdown state.

Parameters
stateReference to LifeCycle node state
Returns
SUCCESS or FAILURE

Definition at line 175 of file waypoint_follower.cpp.

◆ resultCallback()

void nav2_waypoint_follower::WaypointFollower::resultCallback ( const rclcpp_action::ClientGoalHandle< ClientT >::WrappedResult &  result)
protected

Action client result callback.

Parameters
resultResult of action server updated asynchronously

Definition at line 419 of file waypoint_follower.cpp.

Referenced by followWaypointsHandler().

Here is the caller graph for this function:

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