SMACC2
Loading...
Searching...
No Matches
cb_navigate_global_position.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 <geometry_msgs/msg/point.hpp>
23#include <geometry_msgs/msg/pose.hpp>
24
26
27namespace cl_nav2z
28{
30{
31 // std::optional<float> yawTolerance;
32 // std::optional<float> yawToleranceX;
33 // std::optional<float> yawToleranceY;
34
35 std::optional<std::string> goalChecker_;
36
37 std::optional<std::string> controllerName_;
38};
39
41{
42public:
43 float goalYaw;
44
46 geometry_msgs::msg::Point goalPosition;
47
49
51 float x, float y, float yaw /*radians*/,
52 std::optional<CbNavigateGlobalPositionOptions> options = std::nullopt);
53
54 void setGoal(const geometry_msgs::msg::Pose & pose);
55
56 virtual void onEntry() override;
57
58 // This is the substate destructor. This code will be executed when the
59 // workflow exits from this substate (that is according to statechart the moment when this object is destroyed)
60 void onExit() override;
61
62 // auxiliary function that defines the motion that is requested to the navigation2 action server
63 void execute();
64
65private:
67};
68} // namespace cl_nav2z
void setGoal(const geometry_msgs::msg::Pose &pose)
void readStartPoseFromParameterServer(ClNav2Z::Goal &goal)