SMACC2
Loading...
Searching...
No Matches
smacc2_client_library
nav2z_client
nav2z_client
include
nav2z_client
client_behaviors
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
24
#include "
cb_nav2z_client_behavior_base.hpp
"
25
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
26
27
namespace
cl_nav2z
28
{
29
class
CbAbsoluteRotate
:
public
CbNav2ZClientBehaviorBase
30
{
31
public
:
32
std::shared_ptr<tf2_ros::Buffer>
listener
;
33
34
float
absoluteGoalAngleDegree
;
35
std::optional<float>
yawGoalTolerance
;
36
std::optional<float>
maxVelTheta
;
// if not defined, default parameter server
37
std::optional<SpinningPlanner>
spinningPlanner
;
38
39
CbAbsoluteRotate
();
40
CbAbsoluteRotate
(
float
absoluteGoalAngleDegree
,
float
yawGoalTolerance
= -1);
41
42
void
onEntry
()
override
;
43
void
onExit
()
override
;
44
45
private
:
46
void
updateTemporalBehaviorParameters
(
bool
undo);
47
float
oldYawTolerance
;
48
float
oldMaxVelTheta
;
49
float
oldMinVelTheta
;
50
};
51
}
// namespace cl_nav2z
cb_nav2z_client_behavior_base.hpp
cl_nav2z::CbAbsoluteRotate
Definition
cb_absolute_rotate.hpp:30
cl_nav2z::CbAbsoluteRotate::oldMaxVelTheta
float oldMaxVelTheta
Definition
cb_absolute_rotate.hpp:48
cl_nav2z::CbAbsoluteRotate::CbAbsoluteRotate
CbAbsoluteRotate()
Definition
cb_absolute_rotate.cpp:32
cl_nav2z::CbAbsoluteRotate::maxVelTheta
std::optional< float > maxVelTheta
Definition
cb_absolute_rotate.hpp:36
cl_nav2z::CbAbsoluteRotate::oldMinVelTheta
float oldMinVelTheta
Definition
cb_absolute_rotate.hpp:49
cl_nav2z::CbAbsoluteRotate::spinningPlanner
std::optional< SpinningPlanner > spinningPlanner
Definition
cb_absolute_rotate.hpp:37
cl_nav2z::CbAbsoluteRotate::onEntry
void onEntry() override
Definition
cb_absolute_rotate.cpp:43
cl_nav2z::CbAbsoluteRotate::onExit
void onExit() override
Definition
cb_absolute_rotate.cpp:258
cl_nav2z::CbAbsoluteRotate::updateTemporalBehaviorParameters
void updateTemporalBehaviorParameters(bool undo)
Definition
cb_absolute_rotate.cpp:101
cl_nav2z::CbAbsoluteRotate::absoluteGoalAngleDegree
float absoluteGoalAngleDegree
Definition
cb_absolute_rotate.hpp:34
cl_nav2z::CbAbsoluteRotate::listener
std::shared_ptr< tf2_ros::Buffer > listener
Definition
cb_absolute_rotate.hpp:32
cl_nav2z::CbAbsoluteRotate::yawGoalTolerance
std::optional< float > yawGoalTolerance
Definition
cb_absolute_rotate.hpp:35
cl_nav2z::CbAbsoluteRotate::oldYawTolerance
float oldYawTolerance
Definition
cb_absolute_rotate.hpp:47
cl_nav2z::CbNav2ZClientBehaviorBase
Definition
cb_nav2z_client_behavior_base.hpp:29
cl_nav2z
Definition
backward_global_planner.hpp:28
Generated by
1.9.8