include
dwb_plugins
kinematic_parameters.h
Go to the documentation of this file.
1
/*
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2017, Locus Robotics
5
* All rights reserved.
6
*
7
* Redistribution and use in source and binary forms, with or without
8
* modification, are permitted provided that the following conditions
9
* are met:
10
*
11
* * Redistributions of source code must retain the above copyright
12
* notice, this list of conditions and the following disclaimer.
13
* * Redistributions in binary form must reproduce the above
14
* copyright notice, this list of conditions and the following
15
* disclaimer in the documentation and/or other materials provided
16
* with the distribution.
17
* * Neither the name of the copyright holder nor the names of its
18
* contributors may be used to endorse or promote products derived
19
* from this software without specific prior written permission.
20
*
21
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32
* POSSIBILITY OF SUCH DAMAGE.
33
*/
34
35
#ifndef DWB_PLUGINS_KINEMATIC_PARAMETERS_H
36
#define DWB_PLUGINS_KINEMATIC_PARAMETERS_H
37
38
#include <
ros/ros.h
>
39
#include <dynamic_reconfigure/server.h>
40
#include <dwb_plugins/KinematicParamsConfig.h>
41
#include <memory>
42
43
namespace
dwb_plugins
44
{
45
50
class
KinematicParameters
51
{
52
public
:
53
KinematicParameters
();
54
void
initialize
(
const
ros::NodeHandle
& nh);
55
56
inline
double
getMinX
() {
return
min_vel_x_
; }
57
inline
double
getMaxX
() {
return
max_vel_x_
; }
58
inline
double
getAccX
() {
return
acc_lim_x_
; }
59
inline
double
getDecelX
() {
return
decel_lim_x_
; }
60
61
inline
double
getMinY
() {
return
min_vel_y_
; }
62
inline
double
getMaxY
() {
return
max_vel_y_
; }
63
inline
double
getAccY
() {
return
acc_lim_y_
; }
64
inline
double
getDecelY
() {
return
decel_lim_y_
; }
65
66
inline
double
getMinSpeedXY
() {
return
min_speed_xy_
; }
67
68
inline
double
getMinTheta
() {
return
-
max_vel_theta_
; }
69
inline
double
getMaxTheta
() {
return
max_vel_theta_
; }
70
inline
double
getAccTheta
() {
return
acc_lim_theta_
; }
71
inline
double
getDecelTheta
() {
return
decel_lim_theta_
; }
72
inline
double
getMinSpeedTheta
() {
return
min_speed_theta_
; }
73
90
bool
isValidSpeed
(
double
x,
double
y,
double
theta);
91
92
using
Ptr
= std::shared_ptr<KinematicParameters>;
93
protected
:
94
// For parameter descriptions, see cfg/KinematicParams.cfg
95
double
min_vel_x_
,
min_vel_y_
;
96
double
max_vel_x_
,
max_vel_y_
,
max_vel_theta_
;
97
98
double
min_speed_xy_
,
max_speed_xy_
;
99
double
min_speed_theta_
;
100
101
double
acc_lim_x_
,
acc_lim_y_
,
acc_lim_theta_
;
102
double
decel_lim_x_
,
decel_lim_y_
,
decel_lim_theta_
;
103
104
// Cached square values of min_speed_xy and max_speed_xy
105
double
min_speed_xy_sq_
,
max_speed_xy_sq_
;
106
107
void
reconfigureCB
(KinematicParamsConfig &config, uint32_t level);
108
std::shared_ptr<dynamic_reconfigure::Server<KinematicParamsConfig> >
dsrv_
;
109
};
110
111
}
// namespace dwb_plugins
112
113
#endif // DWB_PLUGINS_KINEMATIC_PARAMETERS_H
dwb_plugins::KinematicParameters::max_speed_xy_sq_
double max_speed_xy_sq_
Definition:
kinematic_parameters.h:105
dwb_plugins::KinematicParameters::getMaxTheta
double getMaxTheta()
Definition:
kinematic_parameters.h:69
dwb_plugins::KinematicParameters::max_vel_x_
double max_vel_x_
Definition:
kinematic_parameters.h:96
dwb_plugins::KinematicParameters::initialize
void initialize(const ros::NodeHandle &nh)
Definition:
kinematic_parameters.cpp:74
dwb_plugins::KinematicParameters::max_vel_theta_
double max_vel_theta_
Definition:
kinematic_parameters.h:96
dwb_plugins::KinematicParameters::getDecelTheta
double getDecelTheta()
Definition:
kinematic_parameters.h:71
dwb_plugins::KinematicParameters::dsrv_
std::shared_ptr< dynamic_reconfigure::Server< KinematicParamsConfig > > dsrv_
Definition:
kinematic_parameters.h:108
dwb_plugins::KinematicParameters::getDecelX
double getDecelX()
Definition:
kinematic_parameters.h:59
dwb_plugins::KinematicParameters::min_speed_xy_sq_
double min_speed_xy_sq_
Definition:
kinematic_parameters.h:105
dwb_plugins::KinematicParameters::min_speed_theta_
double min_speed_theta_
Definition:
kinematic_parameters.h:99
ros.h
dwb_plugins::KinematicParameters::max_vel_y_
double max_vel_y_
Definition:
kinematic_parameters.h:96
dwb_plugins::KinematicParameters::getDecelY
double getDecelY()
Definition:
kinematic_parameters.h:64
dwb_plugins::KinematicParameters::KinematicParameters
KinematicParameters()
Definition:
kinematic_parameters.cpp:64
dwb_plugins::KinematicParameters::min_speed_xy_
double min_speed_xy_
Definition:
kinematic_parameters.h:98
dwb_plugins::KinematicParameters::acc_lim_x_
double acc_lim_x_
Definition:
kinematic_parameters.h:101
dwb_plugins::KinematicParameters::getMinY
double getMinY()
Definition:
kinematic_parameters.h:61
dwb_plugins
Definition:
kinematic_parameters.h:43
dwb_plugins::KinematicParameters::acc_lim_theta_
double acc_lim_theta_
Definition:
kinematic_parameters.h:101
dwb_plugins::KinematicParameters::decel_lim_x_
double decel_lim_x_
Definition:
kinematic_parameters.h:102
dwb_plugins::KinematicParameters::isValidSpeed
bool isValidSpeed(double x, double y, double theta)
Check to see whether the combined x/y/theta velocities are valid.
Definition:
kinematic_parameters.cpp:116
dwb_plugins::KinematicParameters::getAccX
double getAccX()
Definition:
kinematic_parameters.h:58
dwb_plugins::KinematicParameters::min_vel_y_
double min_vel_y_
Definition:
kinematic_parameters.h:95
dwb_plugins::KinematicParameters::getMaxY
double getMaxY()
Definition:
kinematic_parameters.h:62
dwb_plugins::KinematicParameters::max_speed_xy_
double max_speed_xy_
Definition:
kinematic_parameters.h:98
dwb_plugins::KinematicParameters::getAccY
double getAccY()
Definition:
kinematic_parameters.h:63
dwb_plugins::KinematicParameters::decel_lim_theta_
double decel_lim_theta_
Definition:
kinematic_parameters.h:102
dwb_plugins::KinematicParameters
A dynamically reconfigurable class containing one representation of the robot's kinematics.
Definition:
kinematic_parameters.h:50
dwb_plugins::KinematicParameters::getMaxX
double getMaxX()
Definition:
kinematic_parameters.h:57
dwb_plugins::KinematicParameters::decel_lim_y_
double decel_lim_y_
Definition:
kinematic_parameters.h:102
dwb_plugins::KinematicParameters::getMinSpeedXY
double getMinSpeedXY()
Definition:
kinematic_parameters.h:66
dwb_plugins::KinematicParameters::acc_lim_y_
double acc_lim_y_
Definition:
kinematic_parameters.h:101
dwb_plugins::KinematicParameters::min_vel_x_
double min_vel_x_
Definition:
kinematic_parameters.h:95
dwb_plugins::KinematicParameters::getMinX
double getMinX()
Definition:
kinematic_parameters.h:56
dwb_plugins::KinematicParameters::reconfigureCB
void reconfigureCB(KinematicParamsConfig &config, uint32_t level)
Definition:
kinematic_parameters.cpp:94
dwb_plugins::KinematicParameters::getMinSpeedTheta
double getMinSpeedTheta()
Definition:
kinematic_parameters.h:72
dwb_plugins::KinematicParameters::Ptr
std::shared_ptr< KinematicParameters > Ptr
Definition:
kinematic_parameters.h:92
dwb_plugins::KinematicParameters::getAccTheta
double getAccTheta()
Definition:
kinematic_parameters.h:70
dwb_plugins::KinematicParameters::getMinTheta
double getMinTheta()
Definition:
kinematic_parameters.h:68
ros::NodeHandle
dwb_plugins
Author(s):
autogenerated on Sun May 18 2025 02:47:27