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