SMACC2
Loading...
Searching...
No Matches
smacc2_client_library
nav2z_client
nav2z_client
include
nav2z_client
client_behaviors
cb_position_control_free_space.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 <
nav2z_client/components/pose/cp_pose.hpp
>
25
#include <
smacc2/smacc_asynchronous_client_behavior.hpp
>
26
27
namespace
cl_nav2z
28
{
29
struct
CbPositionControlFreeSpace
:
public
smacc2::SmaccAsyncClientBehavior
30
{
31
private
:
32
double
targetYaw_
;
33
bool
goalReached_
;
34
double
k_betta_
;
35
double
max_angular_yaw_speed_
;
36
37
double
prev_error_linear_
= 0.0;
38
double
prev_error_angular_
= 0.0;
39
double
integral_linear_
= 0.0;
40
double
integral_angular_
= 0.0;
41
42
// Limit the maximum linear velocity and angular velocity to avoid sudden
43
// movements
44
double
max_linear_velocity
= 1.0;
// Adjust this value according to your needs
45
double
max_angular_velocity
= 1.0;
// Adjust this value according to your needs
46
47
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr
cmd_vel_pub_
;
48
49
public
:
50
double
yaw_goal_tolerance_rads_
= 0.1;
51
52
double
threshold_distance_
= 3.0;
53
54
geometry_msgs::msg::Pose
target_pose_
;
55
56
CbPositionControlFreeSpace
();
57
58
void
updateParameters
();
59
60
void
onEntry
()
override
;
61
62
void
onExit
()
override
;
63
};
64
}
// namespace cl_nav2z
smacc2::SmaccAsyncClientBehavior
Definition
smacc_asynchronous_client_behavior.hpp:56
cp_pose.hpp
cl_nav2z
Definition
backward_global_planner.hpp:28
smacc_asynchronous_client_behavior.hpp
cl_nav2z::CbPositionControlFreeSpace
Definition
cb_position_control_free_space.hpp:30
cl_nav2z::CbPositionControlFreeSpace::max_angular_yaw_speed_
double max_angular_yaw_speed_
Definition
cb_position_control_free_space.hpp:35
cl_nav2z::CbPositionControlFreeSpace::prev_error_angular_
double prev_error_angular_
Definition
cb_position_control_free_space.hpp:38
cl_nav2z::CbPositionControlFreeSpace::threshold_distance_
double threshold_distance_
Definition
cb_position_control_free_space.hpp:52
cl_nav2z::CbPositionControlFreeSpace::k_betta_
double k_betta_
Definition
cb_position_control_free_space.hpp:34
cl_nav2z::CbPositionControlFreeSpace::yaw_goal_tolerance_rads_
double yaw_goal_tolerance_rads_
Definition
cb_position_control_free_space.hpp:50
cl_nav2z::CbPositionControlFreeSpace::goalReached_
bool goalReached_
Definition
cb_position_control_free_space.hpp:33
cl_nav2z::CbPositionControlFreeSpace::updateParameters
void updateParameters()
Definition
cb_position_control_free_space.cpp:35
cl_nav2z::CbPositionControlFreeSpace::onEntry
void onEntry() override
Definition
cb_position_control_free_space.cpp:37
cl_nav2z::CbPositionControlFreeSpace::cmd_vel_pub_
rclcpp::Publisher< geometry_msgs::msg::Twist >::SharedPtr cmd_vel_pub_
Definition
cb_position_control_free_space.hpp:47
cl_nav2z::CbPositionControlFreeSpace::max_angular_velocity
double max_angular_velocity
Definition
cb_position_control_free_space.hpp:45
cl_nav2z::CbPositionControlFreeSpace::target_pose_
geometry_msgs::msg::Pose target_pose_
Definition
cb_position_control_free_space.hpp:54
cl_nav2z::CbPositionControlFreeSpace::max_linear_velocity
double max_linear_velocity
Definition
cb_position_control_free_space.hpp:44
cl_nav2z::CbPositionControlFreeSpace::integral_angular_
double integral_angular_
Definition
cb_position_control_free_space.hpp:40
cl_nav2z::CbPositionControlFreeSpace::prev_error_linear_
double prev_error_linear_
Definition
cb_position_control_free_space.hpp:37
cl_nav2z::CbPositionControlFreeSpace::onExit
void onExit() override
Definition
cb_position_control_free_space.cpp:197
cl_nav2z::CbPositionControlFreeSpace::CbPositionControlFreeSpace
CbPositionControlFreeSpace()
Definition
cb_position_control_free_space.cpp:30
cl_nav2z::CbPositionControlFreeSpace::integral_linear_
double integral_linear_
Definition
cb_position_control_free_space.hpp:39
cl_nav2z::CbPositionControlFreeSpace::targetYaw_
double targetYaw_
Definition
cb_position_control_free_space.hpp:32
Generated by
1.9.8