SMACC2
Loading...
Searching...
No Matches
waypoints_navigator.hpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20#pragma once
21
24#include <smacc2/smacc.hpp>
25
26#include <geometry_msgs/msg/pose.hpp>
27
28namespace cl_nav2z
29{
30class ClNav2Z;
31
32struct Pose2D
33{
34 Pose2D(double x, double y, double yaw)
35 {
36 this->x_ = x;
37 this->y_ = y;
38 this->yaw_ = yaw;
39 }
40
41 double x_;
42 double y_;
43 double yaw_;
44};
45
47{
48 std::optional<std::string> controllerName_;
49 std::optional<std::string> goalCheckerName_;
50};
51
52// This component contains a list of waypoints. These waypoints can
53// be iterated in the different states using CbNextWaiPoint
54// waypoint index is only incremented if the current waypoint is successfully reached
56{
57public:
59
61
63
64 void onInitialize() override;
65
66 template <typename TOrthogonal, typename TSourceObject>
68 {
69 waypointsEventDispatcher.initialize<TSourceObject, TOrthogonal>(client_);
70 }
71
72 void loadWayPointsFromFile(std::string filepath);
73
74 void loadWayPointsFromFile2(std::string filepath);
75
76 void setWaypoints(const std::vector<geometry_msgs::msg::Pose> & waypoints);
77
78 void setWaypoints(const std::vector<Pose2D> & waypoints);
79
80 std::optional<std::shared_future<
81 std::shared_ptr<rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose> > > >
83 std::optional<NavigateNextWaypointOptions> options = std::nullopt,
86
87 void stopWaitingResult();
88
89 const std::vector<geometry_msgs::msg::Pose> & getWaypoints() const;
90 const std::vector<std::string> & getWaypointNames() const;
91 std::optional<geometry_msgs::msg::Pose> getNamedPose(std::string name) const;
92
93 long getCurrentWaypointIndex() const;
94 std::optional<std::string> getCurrentWaypointName() const;
95
97
98 void rewind(int count);
99
100 void forward(int count);
101 void seekName(std::string name);
102
106
107private:
108 void insertWaypoint(int index, geometry_msgs::msg::Pose & newpose);
109
110 void removeWaypoint(int index);
111
113
114 void onGoalReached(const ClNav2Z::WrappedResult & res);
115 void onGoalCancelled(const ClNav2Z::WrappedResult & /*res*/);
116 void onGoalAborted(const ClNav2Z::WrappedResult & /*res*/);
117
118 std::vector<geometry_msgs::msg::Pose> waypoints_;
119
120 std::vector<std::string> waypointsNames_;
121
122 boost::signals2::connection succeddedNav2ZClientConnection_;
123 boost::signals2::connection abortedNav2ZClientConnection_;
124 boost::signals2::connection cancelledNav2ZClientConnection_;
125};
126} // namespace cl_nav2z
boost::signals2::connection cancelledNav2ZClientConnection_
void loadWayPointsFromFile2(std::string filepath)
void onGoalCancelled(const ClNav2Z::WrappedResult &)
std::optional< geometry_msgs::msg::Pose > getNamedPose(std::string name) const
const std::vector< geometry_msgs::msg::Pose > & getWaypoints() const
boost::signals2::connection abortedNav2ZClientConnection_
std::vector< std::string > waypointsNames_
void onNavigationResult(const ClNav2Z::WrappedResult &r)
WaypointEventDispatcher waypointsEventDispatcher
boost::signals2::connection succeddedNav2ZClientConnection_
smacc2::SmaccSignal< void()> onNavigationRequestCancelled
void onGoalReached(const ClNav2Z::WrappedResult &res)
std::optional< std::shared_future< std::shared_ptr< rclcpp_action::ClientGoalHandle< nav2_msgs::action::NavigateToPose > > > > sendNextGoal(std::optional< NavigateNextWaypointOptions > options=std::nullopt, cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::WeakPtr callback=cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::WeakPtr())
smacc2::SmaccSignal< void()> onNavigationRequestAborted
std::vector< geometry_msgs::msg::Pose > waypoints_
void seekName(std::string name)
void loadWayPointsFromFile(std::string filepath)
const std::vector< std::string > & getWaypointNames() const
std::optional< std::string > getCurrentWaypointName() const
void onGoalAborted(const ClNav2Z::WrappedResult &)
smacc2::SmaccSignal< void()> onNavigationRequestSucceded
void setWaypoints(const std::vector< geometry_msgs::msg::Pose > &waypoints)
void insertWaypoint(int index, geometry_msgs::msg::Pose &newpose)
std::weak_ptr< SmaccSignal< void(const WrappedResult &), optional_last_value< typename boost::function_traits< void(const WrappedResult &) >::result_type >, int, std::less< int >, function< void(const WrappedResult &) >, typename extended_signature< function_traits< void(const WrappedResult &) >::arity, void(const WrappedResult &) >::function_type, boost::signals2::mutex > > WeakPtr
std::optional< std::string > controllerName_
std::optional< std::string > goalCheckerName_
Pose2D(double x, double y, double yaw)