Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
limited_accel_generator.cpp
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 #include "dwb_plugins/limited_accel_generator.hpp"
36 #include <vector>
37 #include <memory>
38 #include <string>
39 #include "pluginlib/class_list_macros.hpp"
40 #include "dwb_core/exceptions.hpp"
41 #include "nav2_ros_common/node_utils.hpp"
42 
43 namespace dwb_plugins
44 {
45 
47  const nav2::LifecycleNode::SharedPtr & nh,
48  const std::string & plugin_name)
49 {
50  plugin_name_ = plugin_name;
52 
53  try {
54  nav2::declare_parameter_if_not_declared(
55  nh, plugin_name + ".sim_period", rclcpp::PARAMETER_DOUBLE);
56  if (!nh->get_parameter(plugin_name + ".sim_period", acceleration_time_)) {
57  // This actually should never appear, since declare_parameter_if_not_declared()
58  // completed w/o exceptions guarantee that static parameter will be initialized
59  // with some value. However for reliability we should also process the case
60  // when get_parameter() will return a failure for some other reasons.
61  throw std::runtime_error("Failed to get 'sim_period' value");
62  }
63  } catch (std::exception &) {
64  RCLCPP_WARN(
65  rclcpp::get_logger("LimitedAccelGenerator"),
66  "'sim_period' parameter is not set for %s", plugin_name.c_str());
67  double controller_frequency = nh->declare_or_get_parameter("controller_frequency", 20.0);
68  if (controller_frequency > 0) {
69  acceleration_time_ = 1.0 / controller_frequency;
70  } else {
71  RCLCPP_WARN(
72  rclcpp::get_logger("LimitedAccelGenerator"),
73  "A controller_frequency less than or equal to 0 has been set. "
74  "Ignoring the parameter, assuming a rate of 20Hz");
75  acceleration_time_ = 0.05;
76  }
77  }
78 }
79 
80 void LimitedAccelGenerator::startNewIteration(const nav_2d_msgs::msg::Twist2D & current_velocity)
81 {
82  // Limit our search space to just those within the limited acceleration_time
83  velocity_iterator_->startNewIteration(current_velocity, acceleration_time_);
84 }
85 
87  const nav_2d_msgs::msg::Twist2D & cmd_vel,
88  const nav_2d_msgs::msg::Twist2D & /*start_vel*/,
89  const double /*dt*/)
90 {
91  return cmd_vel;
92 }
93 
94 } // namespace dwb_plugins
95 
Interface for iterating through possible velocities and creating trajectories.
Limits the acceleration in the generated trajectories to a fraction of the simulated time.
void startNewIteration(const nav_2d_msgs::msg::Twist2D &current_velocity) override
Start a new iteration based on the current velocity.
nav_2d_msgs::msg::Twist2D computeNewVelocity(const nav_2d_msgs::msg::Twist2D &cmd_vel, const nav_2d_msgs::msg::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(const nav2::LifecycleNode::SharedPtr &nh, const std::string &plugin_name) override
Initialize parameters as needed.
void initialize(const nav2::LifecycleNode::SharedPtr &nh, const std::string &plugin_name) override
Initialize parameters as needed.