limited_accel_generator.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 
38 #include <nav_core2/exceptions.h>
39 #include <vector>
40 
41 namespace dwb_plugins
42 {
43 
45 {
47  if (nh.hasParam("sim_period"))
48  {
49  nh.getParam("sim_period", acceleration_time_);
50  }
51  else
52  {
53  double controller_frequency = nav_2d_utils::searchAndGetParam(nh, "controller_frequency", 20.0);
54  if (controller_frequency > 0)
55  {
56  acceleration_time_ = 1.0 / controller_frequency;
57  }
58  else
59  {
60  ROS_WARN_NAMED("LimitedAccelGenerator", "A controller_frequency less than or equal to 0 has been set. "
61  "Ignoring the parameter, assuming a rate of 20Hz");
62  acceleration_time_ = 0.05;
63  }
64  }
65 }
66 
68 {
69  bool use_dwa;
70  nh.param("use_dwa", use_dwa, true);
71  if (!use_dwa)
72  {
73  throw nav_core2::PlannerException("Deprecated parameter use_dwa set to false. "
74  "Please use StandardTrajectoryGenerator for that functionality.");
75  }
76 }
77 
78 void LimitedAccelGenerator::startNewIteration(const nav_2d_msgs::Twist2D& current_velocity)
79 {
80  // Limit our search space to just those within the limited acceleration_time
81  velocity_iterator_->startNewIteration(current_velocity, acceleration_time_);
82 }
83 
84 nav_2d_msgs::Twist2D LimitedAccelGenerator::computeNewVelocity(const nav_2d_msgs::Twist2D& cmd_vel,
85  const nav_2d_msgs::Twist2D& start_vel, const double dt)
86 {
87  return cmd_vel;
88 }
89 
90 } // namespace dwb_plugins
91 
void startNewIteration(const nav_2d_msgs::Twist2D &current_velocity) override
#define ROS_WARN_NAMED(name,...)
param_t searchAndGetParam(const ros::NodeHandle &nh, const std::string &param_name, const param_t &default_value)
Limits the acceleration in the generated trajectories to a fraction of the simulated time...
void initialize(ros::NodeHandle &nh) override
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void checkUseDwaParam(const ros::NodeHandle &nh) override
Check if the deprecated use_dwa parameter is set to the functionality that matches this class...
std::shared_ptr< VelocityIterator > velocity_iterator_
bool getParam(const std::string &key, std::string &s) const
bool hasParam(const std::string &key) const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
nav_2d_msgs::Twist2D computeNewVelocity(const nav_2d_msgs::Twist2D &cmd_vel, const nav_2d_msgs::Twist2D &start_vel, const double dt) override
Calculate the velocity after a set period of time, given the desired velocity and acceleration limits...
void initialize(ros::NodeHandle &nh) override


dwb_plugins
Author(s):
autogenerated on Wed Jun 26 2019 20:06:16