SMACC2
Loading...
Searching...
No Matches
cp_waypoints_navigator_base.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
22#include <cl_nav2z/cl_nav2z.hpp>
24#include <smacc2/smacc.hpp>
25
26#include <geometry_msgs/msg/pose.hpp>
27
28namespace cl_nav2z
29{
30struct Pose2D
31{
32 Pose2D(double x, double y, double yaw)
33 {
34 this->x_ = x;
35 this->y_ = y;
36 this->yaw_ = yaw;
37 }
38
39 double x_;
40 double y_;
41 double yaw_;
42};
43
44// This component contains a list of waypoints. These waypoints can
45// be iterated in the different states using CbNextWaiPoint
46// waypoint index is only incremented if the current waypoint is successfully reached
48{
49public:
51
53
55
56 void onInitialize() override;
57
58 template <typename TOrthogonal, typename TSourceObject>
60 {
61 ClNav2Z * client = dynamic_cast<ClNav2Z *>(owner_);
62 waypointsEventDispatcher.initialize<TSourceObject, TOrthogonal>(client);
63 }
64
65 void loadWayPointsFromFile(std::string filepath);
66
67 void loadWayPointsFromFile2(std::string filepath);
68
69 void setWaypoints(const std::vector<geometry_msgs::msg::Pose> & waypoints);
70
71 void setWaypoints(const std::vector<Pose2D> & waypoints);
72
73 const std::vector<geometry_msgs::msg::Pose> & getWaypoints() const;
74 const std::vector<std::string> & getWaypointNames() const;
75 std::optional<geometry_msgs::msg::Pose> getNamedPose(std::string name) const;
76 geometry_msgs::msg::Pose getPose(int index) const;
77 geometry_msgs::msg::Pose getCurrentPose() const;
78
79 long getCurrentWaypointIndex() const;
80 std::optional<std::string> getCurrentWaypointName() const;
81
83
84 void rewind(int count);
85
86 void forward(int count);
87 void seekName(std::string name);
88
90 std::string parameter_name, std::string yaml_file_package_name);
91
92 void notifyGoalReached();
93
94protected:
95 void insertWaypoint(int index, geometry_msgs::msg::Pose & newpose);
96
97 void removeWaypoint(int index);
98
99 std::vector<geometry_msgs::msg::Pose> waypoints_;
100
101 std::vector<std::string> waypointsNames_;
102};
103} // namespace cl_nav2z
void setWaypoints(const std::vector< geometry_msgs::msg::Pose > &waypoints)
const std::vector< geometry_msgs::msg::Pose > & getWaypoints() const
void loadWayPointsFromFile2(std::string filepath)
std::vector< geometry_msgs::msg::Pose > waypoints_
geometry_msgs::msg::Pose getCurrentPose() const
void loadWayPointsFromFile(std::string filepath)
std::optional< std::string > getCurrentWaypointName() const
std::optional< geometry_msgs::msg::Pose > getNamedPose(std::string name) const
geometry_msgs::msg::Pose getPose(int index) const
const std::vector< std::string > & getWaypointNames() const
void loadWaypointsFromYamlParameter(std::string parameter_name, std::string yaml_file_package_name)
void insertWaypoint(int index, geometry_msgs::msg::Pose &newpose)
ISmaccClient * owner_
Definition component.hpp:88
Pose2D(double x, double y, double yaw)