kinematic_parameters.cpp
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 
37 #include <memory>
38 #include <string>
39 
41 namespace dwb_plugins
42 {
43 
44 const double EPSILON = 1E-5;
45 
51 void setDecelerationAsNeeded(const ros::NodeHandle& nh, const std::string dimension)
52 {
53  std::string decel_param = "decel_lim_" + dimension;
54  if (nh.hasParam(decel_param)) return;
55 
56  std::string accel_param = "acc_lim_" + dimension;
57  if (!nh.hasParam(accel_param)) return;
58 
59  double accel;
60  nh.getParam(accel_param, accel);
61  nh.setParam(decel_param, -accel);
62 }
63 
65  min_vel_x_(0.0), min_vel_y_(0.0), max_vel_x_(0.0), max_vel_y_(0.0), max_vel_theta_(0.0),
66  min_speed_xy_(0.0), max_speed_xy_(0.0), min_speed_theta_(0.0),
67  acc_lim_x_(0.0), acc_lim_y_(0.0), acc_lim_theta_(0.0),
68  decel_lim_x_(0.0), decel_lim_y_(0.0), decel_lim_theta_(0.0),
69  min_speed_xy_sq_(0.0), max_speed_xy_sq_(0.0),
70  dsrv_(nullptr)
71 {
72 }
73 
75 {
76  // Special handling for renamed parameters
77  moveDeprecatedParameter<double>(nh, "max_vel_theta", "max_rot_vel");
78  moveDeprecatedParameter<double>(nh, "min_speed_xy", "min_trans_vel");
79  moveDeprecatedParameter<double>(nh, "max_speed_xy", "max_trans_vel");
80  moveDeprecatedParameter<double>(nh, "min_speed_theta", "min_rot_vel");
81 
82  // Set the deceleration parameters to negative the acceleration if the deceleration not already specified
83  setDecelerationAsNeeded(nh, "x");
84  setDecelerationAsNeeded(nh, "y");
85  setDecelerationAsNeeded(nh, "theta");
86 
87  // the rest of the initial values are loaded through the dynamic reconfigure mechanisms
88  dsrv_ = std::make_shared<dynamic_reconfigure::Server<KinematicParamsConfig> >(nh);
89  dynamic_reconfigure::Server<KinematicParamsConfig>::CallbackType cb =
90  boost::bind(&KinematicParameters::reconfigureCB, this, _1, _2);
91  dsrv_->setCallback(cb);
92 }
93 
94 void KinematicParameters::reconfigureCB(KinematicParamsConfig &config, uint32_t level)
95 {
96  min_vel_x_ = config.min_vel_x;
97  min_vel_y_ = config.min_vel_y;
98  max_vel_x_ = config.max_vel_x;
99  max_vel_y_ = config.max_vel_y;
100  max_vel_theta_ = config.max_vel_theta;
101 
102  min_speed_xy_ = config.min_speed_xy;
103  max_speed_xy_ = config.max_speed_xy;
106  min_speed_theta_ = config.min_speed_theta;
107 
108  acc_lim_x_ = config.acc_lim_x;
109  acc_lim_y_ = config.acc_lim_y;
110  acc_lim_theta_ = config.acc_lim_theta;
111  decel_lim_x_ = config.decel_lim_x;
112  decel_lim_y_ = config.decel_lim_y;
113  decel_lim_theta_ = config.decel_lim_theta;
114 }
115 
116 bool KinematicParameters::isValidSpeed(double x, double y, double theta)
117 {
118  double vmag_sq = x * x + y * y;
119  if (max_speed_xy_ >= 0.0 && vmag_sq > max_speed_xy_sq_ + EPSILON) return false;
120  if (min_speed_xy_ >= 0.0 && vmag_sq + EPSILON < min_speed_xy_sq_ &&
121  min_speed_theta_ >= 0.0 && fabs(theta) + EPSILON < min_speed_theta_) return false;
122  if (vmag_sq == 0.0 && theta == 0.0) return false;
123  return true;
124 }
125 
126 } // namespace dwb_plugins
void moveDeprecatedParameter(const ros::NodeHandle &nh, const std::string current_name, const std::string old_name)
void reconfigureCB(KinematicParamsConfig &config, uint32_t level)
const double EPSILON
std::shared_ptr< dynamic_reconfigure::Server< KinematicParamsConfig > > dsrv_
void initialize(const ros::NodeHandle &nh)
bool getParam(const std::string &key, std::string &s) const
bool hasParam(const std::string &key) const
bool isValidSpeed(double x, double y, double theta)
Check to see whether the combined x/y/theta velocities are valid.
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
void setDecelerationAsNeeded(const ros::NodeHandle &nh, const std::string dimension)
Helper function to set the deceleration to the negative acceleration if it was not already set...


dwb_plugins
Author(s):
autogenerated on Sun Jan 10 2021 04:08:37