SMACC2
Loading...
Searching...
No Matches
cb_absolute_rotate.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_ros/buffer.h>
23
25#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
26
27namespace cl_nav2z
28{
30{
31public:
32 std::shared_ptr<tf2_ros::Buffer> listener;
33
35 std::optional<float> yawGoalTolerance;
36 std::optional<float> maxVelTheta; // if not defined, default parameter server
37 std::optional<SpinningPlanner> spinningPlanner;
38
41
42 void onEntry() override;
43 void onExit() override;
44
45private:
50};
51} // namespace cl_nav2z
std::optional< float > maxVelTheta
std::optional< SpinningPlanner > spinningPlanner
void updateTemporalBehaviorParameters(bool undo)
std::shared_ptr< tf2_ros::Buffer > listener
std::optional< float > yawGoalTolerance