SMACC2
Loading...
Searching...
No Matches
smacc2_client_library
nav2z_client
nav2z_client
include
nav2z_client
client_behaviors
cb_pure_spinning.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
21
#pragma once
22
23
#include <geometry_msgs/msg/twist.hpp>
24
#include <
smacc2/smacc_asynchronous_client_behavior.hpp
>
25
26
namespace
cl_nav2z
27
{
28
struct
CbPureSpinning
:
public
smacc2::SmaccAsyncClientBehavior
29
{
30
private
:
31
double
targetYaw__rads
;
32
bool
goalReached_
;
33
double
k_betta_
;
34
double
max_angular_yaw_speed_
;
35
36
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr
cmd_vel_pub_
;
37
38
public
:
39
double
yaw_goal_tolerance_rads_
;
40
41
CbPureSpinning
(
double
targetYaw_rads,
double
max_angular_yaw_speed = 0.5);
42
void
updateParameters
();
43
44
void
onEntry
()
override
;
45
46
void
onExit
()
override
;
47
};
48
}
// namespace cl_nav2z
smacc2::SmaccAsyncClientBehavior
Definition
smacc_asynchronous_client_behavior.hpp:56
cl_nav2z
Definition
backward_global_planner.hpp:28
smacc_asynchronous_client_behavior.hpp
cl_nav2z::CbPureSpinning
Definition
cb_pure_spinning.hpp:29
cl_nav2z::CbPureSpinning::targetYaw__rads
double targetYaw__rads
Definition
cb_pure_spinning.hpp:31
cl_nav2z::CbPureSpinning::k_betta_
double k_betta_
Definition
cb_pure_spinning.hpp:33
cl_nav2z::CbPureSpinning::updateParameters
void updateParameters()
Definition
cb_pure_spinning.cpp:37
cl_nav2z::CbPureSpinning::yaw_goal_tolerance_rads_
double yaw_goal_tolerance_rads_
Definition
cb_pure_spinning.hpp:39
cl_nav2z::CbPureSpinning::onEntry
void onEntry() override
Definition
cb_pure_spinning.cpp:39
cl_nav2z::CbPureSpinning::goalReached_
bool goalReached_
Definition
cb_pure_spinning.hpp:32
cl_nav2z::CbPureSpinning::max_angular_yaw_speed_
double max_angular_yaw_speed_
Definition
cb_pure_spinning.hpp:34
cl_nav2z::CbPureSpinning::cmd_vel_pub_
rclcpp::Publisher< geometry_msgs::msg::Twist >::SharedPtr cmd_vel_pub_
Definition
cb_pure_spinning.hpp:36
cl_nav2z::CbPureSpinning::onExit
void onExit() override
Definition
cb_pure_spinning.cpp:101
Generated by
1.9.8