An action server that uses behavior tree for navigating a robot to its goal position.
More...
|
| 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.
|
|
| 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::LifecycleNode > | shared_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.
|
|
|
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...
|
|
void | printLifecycleNodeNotification () |
| Print notifications for lifecycle node.
|
|
void | register_rcl_preshutdown_callback () |
|
void | runCleanups () |
|
|
std::vector< int > | failed_ids_ |
|
std::string | global_frame_id_ {"map"} |
|
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | dyn_params_handler_ |
|
std::unique_ptr< ActionServer > | xyz_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< ActionServerGPS > | gps_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::WaypointTaskExecutor > | waypoint_task_executor_loader_ |
|
pluginlib::UniquePtr< nav2_core::WaypointTaskExecutor > | waypoint_task_executor_ |
|
std::string | waypoint_task_executor_id_ |
|
std::string | waypoint_task_executor_type_ |
|
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_ |
|
An action server that uses behavior tree for navigating a robot to its goal position.
Definition at line 67 of file waypoint_follower.hpp.
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
-
T | action_server |
V | feedback |
Z | result |
- Parameters
-
action_server | |
poses | |
feedback | |
result | |
Definition at line 206 of file waypoint_follower.cpp.
References goalResponseCallback(), and resultCallback().