Nav2 Navigation Stack - rolling  main
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_ros_common/lifecycle_node.hpp"
47 
48 namespace dwb_plugins
49 {
50 
56 {
57 public:
58  // Standard TrajectoryGenerator interface
59  void initialize(
60  const nav2::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::Pose & 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 
88  void activate();
89 
93  void deactivate();
94 
95 protected:
99  virtual void initializeIterator(const nav2::LifecycleNode::SharedPtr & nh);
100 
109  virtual nav_2d_msgs::msg::Twist2D computeNewVelocity(
110  const nav_2d_msgs::msg::Twist2D & cmd_vel, const nav_2d_msgs::msg::Twist2D & start_vel,
111  const double dt);
112 
121  virtual geometry_msgs::msg::Pose computeNewPosition(
122  const geometry_msgs::msg::Pose start_pose, const nav_2d_msgs::msg::Twist2D & vel,
123  const double dt);
124 
125 
138  virtual std::vector<double> getTimeSteps(const nav_2d_msgs::msg::Twist2D & cmd_vel);
139 
140  KinematicsHandler::Ptr kinematics_handler_;
141  std::shared_ptr<VelocityIterator> velocity_iterator_;
142 
143  double sim_time_;
144 
145  // Sampling Parameters
146  bool discretize_by_time_;
147 
150 
153 
156 
158  std::string plugin_name_;
159 
162 
163  /* Backwards Compatibility Parameter: include_last_point
164  *
165  * dwa had an off-by-one error built into it.
166  * It generated N trajectory points, where N = ceil(sim_time / time_delta).
167  * If for example, sim_time=3.0 and time_delta=1.5, it would generate trajectories with 2 points, which
168  * indeed were time_delta seconds apart. However, the points would be at t=0 and t=1.5, and thus the
169  * actual sim_time was much less than advertised.
170  *
171  * This is remedied by adding one final point at t=sim_time, but only if include_last_point_ is true.
172  *
173  * Nothing I could find actually used the time_delta variable or seemed to care that the trajectories
174  * were not projected out as far as they intended.
175  */
176  bool include_last_point_;
177 };
178 
179 
180 } // namespace dwb_plugins
181 
182 #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
void deactivate()
Resets callbacks for dynamic parameter handling.
void activate()
Registers callbacks for dynamic parameter handling.
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.
virtual geometry_msgs::msg::Pose computeNewPosition(const geometry_msgs::msg::Pose 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.
double time_granularity_
If discretizing by time, the amount of time between each point in the traj.
void initialize(const nav2::LifecycleNode::SharedPtr &nh, const std::string &plugin_name) override
Initialize parameters as needed.
virtual void initializeIterator(const nav2::LifecycleNode::SharedPtr &nh)
Initialize the VelocityIterator pointer. Put in its own function for easy overriding.
dwb_msgs::msg::Trajectory2D generateTrajectory(const geometry_msgs::msg::Pose &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.
nav_2d_msgs::msg::Twist2D nextTwist() override
Return the next twist and advance the iteration.