SMACC2
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
46// This component contains a list of waypoints. These waypoints can
47// be iterated in the different states using CbNextWaiPoint
48// waypoint index is only incremented if the current waypoint is successfully reached
50{
51public:
53
55
57
58 void onInitialize() override;
59
60 template <typename TOrthogonal, typename TSourceObject>
62 {
63 waypointsEventDispatcher.initialize<TSourceObject, TOrthogonal>(client_);
64 }
65
66 void loadWayPointsFromFile(std::string filepath);
67
68 void loadWayPointsFromFile2(std::string filepath);
69
70 void setWaypoints(const std::vector<geometry_msgs::msg::Pose> & waypoints);
71
72 void setWaypoints(const std::vector<Pose2D> & waypoints);
73
74 void sendNextGoal();
75 void stopWaitingResult();
76
77 const std::vector<geometry_msgs::msg::Pose> & getWaypoints() const;
78
79 long getCurrentWaypointIndex() const;
80
82
83 void rewind(int count);
84
88
89private:
90 void insertWaypoint(int index, geometry_msgs::msg::Pose & newpose);
91
92 void removeWaypoint(int index);
93
97
98 std::vector<geometry_msgs::msg::Pose> waypoints_;
99
100 std::vector<std::string> waypointsNames_;
101
102 boost::signals2::connection succeddedNav2ZClientConnection_;
103 boost::signals2::connection abortedNav2ZClientConnection_;
104 boost::signals2::connection cancelledNav2ZClientConnection_;
105};
106} // namespace cl_nav2z
boost::signals2::connection cancelledNav2ZClientConnection_
void loadWayPointsFromFile2(std::string filepath)
const std::vector< geometry_msgs::msg::Pose > & getWaypoints() const
void onGoalCancelled(ClNav2Z::WrappedResult &)
boost::signals2::connection abortedNav2ZClientConnection_
std::vector< std::string > waypointsNames_
WaypointEventDispatcher waypointsEventDispatcher
boost::signals2::connection succeddedNav2ZClientConnection_
smacc2::SmaccSignal< void()> onNavigationRequestCancelled
void onGoalAborted(ClNav2Z::WrappedResult &)
smacc2::SmaccSignal< void()> onNavigationRequestAborted
std::vector< geometry_msgs::msg::Pose > waypoints_
void loadWayPointsFromFile(std::string filepath)
void onGoalReached(ClNav2Z::WrappedResult &res)
smacc2::SmaccSignal< void()> onNavigationRequestSucceded
void setWaypoints(const std::vector< geometry_msgs::msg::Pose > &waypoints)
void insertWaypoint(int index, geometry_msgs::msg::Pose &newpose)
Pose2D(double x, double y, double yaw)