SMACC2
Loading...
Searching...
No Matches
cb_navigate_forward.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 <tf2/utils.h>
23#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
24#include <tf2_ros/buffer.h>
25#include <geometry_msgs/msg/pose_stamped.hpp>
27#include <optional>
28
30
31namespace cl_nav2z
32{
34{
35 // just a stub to show how to use parameterless constructor
36 std::optional<float> forwardSpeed;
37
38 // this may be useful in the case you want to do a straight line with some known direction
39 // and the robot may not have that specific initial orientation at that moment.
40 // If it is not set, the orientation of the straight line is the orientation of the initial (current) state.
41 std::optional<geometry_msgs::msg::Quaternion> forceInitialOrientation;
42
43 // the name of the goal checker selected in the navigation2 stack
44 std::optional<std::string> goalChecker_;
45};
46
47// Performs a relative motion forwards
49{
50public:
52
54
55 CbNavigateForward(float forwardDistance);
56
57 // alternative forward motion using an absolute goal position instead a relative linear distance.
58 // It is specially to retry a previous relative incorrect motions based on distance.
59 // The developer user is in charge of setting a valid goal position that is located forward
60 // from the current position and orientation.
61 CbNavigateForward(geometry_msgs::msg::PoseStamped goalPosition);
62
63 virtual ~CbNavigateForward();
64
65 void onEntry() override;
66
67 void onExit() override;
68
69 void setForwardDistance(float distance_meters);
70
71protected:
72 // required component
74
75 std::optional<geometry_msgs::msg::PoseStamped> goalPose_;
76
77 std::optional<float> forwardDistance_;
78};
79} // namespace cl_nav2z
std::optional< geometry_msgs::msg::PoseStamped > goalPose_
std::optional< float > forwardDistance_
CbNavigateForwardOptions options
void setForwardDistance(float distance_meters)
odom_tracker::OdomTracker * odomTracker_
std::optional< geometry_msgs::msg::Quaternion > forceInitialOrientation
std::optional< std::string > goalChecker_