Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
standard_traj_generator.hpp
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__STANDARD_TRAJ_GENERATOR_HPP_
36 #define DWB_PLUGINS__STANDARD_TRAJ_GENERATOR_HPP_
37 
38 #include <vector>
39 #include <memory>
40 #include <string>
41 
42 #include "rclcpp/rclcpp.hpp"
43 #include "dwb_core/trajectory_generator.hpp"
44 #include "dwb_plugins/velocity_iterator.hpp"
45 #include "dwb_plugins/kinematic_parameters.hpp"
46 #include "nav2_util/lifecycle_node.hpp"
47 
48 namespace dwb_plugins
49 {
50 
56 {
57 public:
58  // Standard TrajectoryGenerator interface
59  void initialize(
60  const nav2_util::LifecycleNode::SharedPtr & nh,
61  const std::string & plugin_name) override;
62  void startNewIteration(const nav_2d_msgs::msg::Twist2D & current_velocity) override;
63  bool hasMoreTwists() override;
64  nav_2d_msgs::msg::Twist2D nextTwist() override;
65 
66  dwb_msgs::msg::Trajectory2D generateTrajectory(
67  const geometry_msgs::msg::Pose2D & start_pose,
68  const nav_2d_msgs::msg::Twist2D & start_vel,
69  const nav_2d_msgs::msg::Twist2D & cmd_vel) override;
70 
78  void setSpeedLimit(const double & speed_limit, const bool & percentage) override
79  {
80  if (kinematics_handler_) {
81  kinematics_handler_->setSpeedLimit(speed_limit, percentage);
82  }
83  }
84 
85 protected:
89  virtual void initializeIterator(const nav2_util::LifecycleNode::SharedPtr & nh);
90 
99  virtual nav_2d_msgs::msg::Twist2D computeNewVelocity(
100  const nav_2d_msgs::msg::Twist2D & cmd_vel, const nav_2d_msgs::msg::Twist2D & start_vel,
101  const double dt);
102 
111  virtual geometry_msgs::msg::Pose2D computeNewPosition(
112  const geometry_msgs::msg::Pose2D start_pose, const nav_2d_msgs::msg::Twist2D & vel,
113  const double dt);
114 
115 
128  virtual std::vector<double> getTimeSteps(const nav_2d_msgs::msg::Twist2D & cmd_vel);
129 
130  KinematicsHandler::Ptr kinematics_handler_;
131  std::shared_ptr<VelocityIterator> velocity_iterator_;
132 
133  double sim_time_;
134 
135  // Sampling Parameters
136  bool discretize_by_time_;
137 
140 
143 
146 
148  std::string plugin_name_;
149 
152 
153  /* Backwards Compatibility Parameter: include_last_point
154  *
155  * dwa had an off-by-one error built into it.
156  * It generated N trajectory points, where N = ceil(sim_time / time_delta).
157  * If for example, sim_time=3.0 and time_delta=1.5, it would generate trajectories with 2 points, which
158  * indeed were time_delta seconds apart. However, the points would be at t=0 and t=1.5, and thus the
159  * actual sim_time was much less than advertised.
160  *
161  * This is remedied by adding one final point at t=sim_time, but only if include_last_point_ is true.
162  *
163  * Nothing I could find actually used the time_delta variable or seemed to care that the trajectories
164  * were not projected out as far as they intended.
165  */
166  bool include_last_point_;
167 };
168 
169 
170 } // namespace dwb_plugins
171 
172 #endif // DWB_PLUGINS__STANDARD_TRAJ_GENERATOR_HPP_
Interface for iterating through possible velocities and creating trajectories.
Standard DWA-like trajectory generator.
void startNewIteration(const nav_2d_msgs::msg::Twist2D &current_velocity) override
Start a new iteration based on the current velocity.
double angular_granularity_
If not discretizing by time, the amount of angular space between points.
virtual 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)
Calculate the velocity after a set period of time, given the desired velocity and acceleration limits...
void setSpeedLimit(const double &speed_limit, const bool &percentage) override
Limits the maximum linear speed of the robot.
std::string plugin_name_
the name of the overlying plugin ID
bool hasMoreTwists() override
Test to see whether there are more twists to test.
virtual std::vector< double > getTimeSteps(const nav_2d_msgs::msg::Twist2D &cmd_vel)
Compute an array of time deltas between the points in the generated trajectory.
bool limit_vel_cmd_in_traj_
Option to limit velocity in the trajectory generator by using current velocity.
double linear_granularity_
If not discretizing by time, the amount of linear space between points.
void initialize(const nav2_util::LifecycleNode::SharedPtr &nh, const std::string &plugin_name) override
Initialize parameters as needed.
double time_granularity_
If discretizing by time, the amount of time between each point in the traj.
dwb_msgs::msg::Trajectory2D generateTrajectory(const geometry_msgs::msg::Pose2D &start_pose, const nav_2d_msgs::msg::Twist2D &start_vel, const nav_2d_msgs::msg::Twist2D &cmd_vel) override
Given a cmd_vel in the robot's frame and initial conditions, generate a Trajectory2D.
virtual geometry_msgs::msg::Pose2D computeNewPosition(const geometry_msgs::msg::Pose2D start_pose, const nav_2d_msgs::msg::Twist2D &vel, const double dt)
Use the robot's kinematic model to predict new positions for the robot.
virtual void initializeIterator(const nav2_util::LifecycleNode::SharedPtr &nh)
Initialize the VelocityIterator pointer. Put in its own function for easy overriding.
nav_2d_msgs::msg::Twist2D nextTwist() override
Return the next twist and advance the iteration.