15 #ifndef NAV2_WAYPOINT_FOLLOWER__WAYPOINT_FOLLOWER_HPP_
16 #define NAV2_WAYPOINT_FOLLOWER__WAYPOINT_FOLLOWER_HPP_
23 #include "rclcpp_action/rclcpp_action.hpp"
24 #include "pluginlib/class_loader.hpp"
25 #include "pluginlib/class_list_macros.hpp"
26 #include "geographic_msgs/msg/geo_pose.hpp"
27 #include "nav2_ros_common/lifecycle_node.hpp"
28 #include "nav2_msgs/action/navigate_to_pose.hpp"
29 #include "nav2_msgs/action/follow_waypoints.hpp"
30 #include "nav2_msgs/msg/waypoint_status.hpp"
31 #include "nav_msgs/msg/path.hpp"
32 #include "nav2_ros_common/simple_action_server.hpp"
33 #include "nav2_ros_common/node_utils.hpp"
34 #include "nav2_util/string_utils.hpp"
35 #include "nav2_msgs/action/follow_gps_waypoints.hpp"
36 #include "nav2_ros_common/service_client.hpp"
37 #include "nav2_core/waypoint_task_executor.hpp"
39 #include "robot_localization/srv/from_ll.hpp"
40 #include "tf2_ros/buffer.hpp"
41 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
42 #include "tf2_ros/transform_listener.hpp"
44 namespace nav2_waypoint_follower
47 enum class ActionStatus
59 std::string error_msg;
70 using ActionT = nav2_msgs::action::FollowWaypoints;
71 using ClientT = nav2_msgs::action::NavigateToPose;
73 using ActionClient = nav2::ActionClient<ClientT>;
76 using ActionTGPS = nav2_msgs::action::FollowGPSWaypoints;
83 explicit WaypointFollower(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
97 nav2::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
103 nav2::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
109 nav2::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
115 nav2::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
121 nav2::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
136 template<
typename T,
typename V,
typename Z>
157 void resultCallback(
const rclcpp_action::ClientGoalHandle<ClientT>::WrappedResult & result);
173 const std::vector<geographic_msgs::msg::GeoPose> & gps_poses);
185 std::vector<geometry_msgs::msg::PoseStamped>
getLatestGoalPoses(
const T & action_server);
188 std::vector<int> failed_ids_;
189 std::string global_frame_id_{
"map"};
195 rcl_interfaces::msg::SetParametersResult
199 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
202 typename ActionServer::SharedPtr xyz_action_server_;
203 ActionClient::SharedPtr nav_to_pose_client_;
204 rclcpp::CallbackGroup::SharedPtr callback_group_;
205 rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
206 std::shared_future<rclcpp_action::ClientGoalHandle<ClientT>::SharedPtr> future_goal_handle_;
209 typename ActionServerGPS::SharedPtr gps_action_server_;
210 nav2::ServiceClient<robot_localization::srv::FromLL>::SharedPtr from_ll_to_map_client_;
212 bool stop_on_failure_;
217 pluginlib::ClassLoader<nav2_core::WaypointTaskExecutor>
218 waypoint_task_executor_loader_;
219 pluginlib::UniquePtr<nav2_core::WaypointTaskExecutor>
220 waypoint_task_executor_;
221 std::string waypoint_task_executor_id_;
222 std::string waypoint_task_executor_type_;
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
An action server wrapper to make applications simpler using Actions.
An action server that uses behavior tree for navigating a robot to its goal position.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates action server.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in shutdown state.
void resultCallback(const rclcpp_action::ClientGoalHandle< ClientT >::WrappedResult &result)
Action client result callback.
~WaypointFollower()
A destructor for nav2_waypoint_follower::WaypointFollower class.
WaypointFollower(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for nav2_waypoint_follower::WaypointFollower class.
void goalResponseCallback(const rclcpp_action::ClientGoalHandle< ClientT >::SharedPtr &goal)
Action client goal response callback.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Resets member variables.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures member variables.
void followGPSWaypointsCallback()
send robot through each of GPS point , which are converted to map frame first then using a client to ...
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....
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...
void followWaypointsCallback()
Action server callbacks.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
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 car...
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates action server.