Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
standard_traj_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/standard_traj_generator.hpp"
36 #include <string>
37 #include <vector>
38 #include <algorithm>
39 #include <memory>
40 #include "dwb_plugins/xy_theta_iterator.hpp"
41 #include "nav_2d_utils/parameters.hpp"
42 #include "pluginlib/class_list_macros.hpp"
43 #include "dwb_core/exceptions.hpp"
44 #include "nav2_util/node_utils.hpp"
45 
46 namespace dwb_plugins
47 {
48 
50  const nav2_util::LifecycleNode::SharedPtr & nh,
51  const std::string & plugin_name)
52 {
53  plugin_name_ = plugin_name;
54  kinematics_handler_ = std::make_shared<KinematicsHandler>();
55  kinematics_handler_->initialize(nh, plugin_name_);
57 
58  nav2_util::declare_parameter_if_not_declared(
59  nh,
60  plugin_name + ".sim_time", rclcpp::ParameterValue(1.7));
61  nav2_util::declare_parameter_if_not_declared(
62  nh,
63  plugin_name + ".discretize_by_time", rclcpp::ParameterValue(false));
64 
65  nav2_util::declare_parameter_if_not_declared(
66  nh,
67  plugin_name + ".time_granularity", rclcpp::ParameterValue(0.5));
68  nav2_util::declare_parameter_if_not_declared(
69  nh,
70  plugin_name + ".linear_granularity", rclcpp::ParameterValue(0.5));
71  nav2_util::declare_parameter_if_not_declared(
72  nh,
73  plugin_name + ".angular_granularity", rclcpp::ParameterValue(0.025));
74  nav2_util::declare_parameter_if_not_declared(
75  nh,
76  plugin_name + ".include_last_point", rclcpp::ParameterValue(true));
77 
78  nav2_util::declare_parameter_if_not_declared(
79  nh,
80  plugin_name + ".limit_vel_cmd_in_traj", rclcpp::ParameterValue(false));
81 
82  /*
83  * If discretize_by_time, then sim_granularity represents the amount of time that should be between
84  * two successive points on the trajectory.
85  *
86  * If discretize_by_time is false, then sim_granularity is the maximum amount of distance between
87  * two successive points on the trajectory, and angular_sim_granularity is the maximum amount of
88  * angular distance between two successive points.
89  */
90  nh->get_parameter(plugin_name + ".sim_time", sim_time_);
91  nh->get_parameter(plugin_name + ".discretize_by_time", discretize_by_time_);
92  nh->get_parameter(plugin_name + ".time_granularity", time_granularity_);
93  nh->get_parameter(plugin_name + ".linear_granularity", linear_granularity_);
94  nh->get_parameter(plugin_name + ".angular_granularity", angular_granularity_);
95  nh->get_parameter(plugin_name + ".include_last_point", include_last_point_);
96  nh->get_parameter(plugin_name + ".limit_vel_cmd_in_traj", limit_vel_cmd_in_traj_);
97 }
98 
100  const nav2_util::LifecycleNode::SharedPtr & nh)
101 {
102  velocity_iterator_ = std::make_shared<XYThetaIterator>();
103  velocity_iterator_->initialize(nh, kinematics_handler_, plugin_name_);
104 }
105 
107  const nav_2d_msgs::msg::Twist2D & current_velocity)
108 {
109  velocity_iterator_->startNewIteration(current_velocity, sim_time_);
110 }
111 
113 {
114  return velocity_iterator_->hasMoreTwists();
115 }
116 
117 nav_2d_msgs::msg::Twist2D StandardTrajectoryGenerator::nextTwist()
118 {
119  return velocity_iterator_->nextTwist();
120 }
121 
123  const nav_2d_msgs::msg::Twist2D & cmd_vel)
124 {
125  std::vector<double> steps;
126  if (discretize_by_time_) {
127  steps.resize(ceil(sim_time_ / time_granularity_));
128  } else { // discretize by distance
129  double vmag = hypot(cmd_vel.x, cmd_vel.y);
130 
131  // the distance the robot would travel in sim_time if it did not change velocity
132  double projected_linear_distance = vmag * sim_time_;
133 
134  // the angle the robot would rotate in sim_time
135  double projected_angular_distance = fabs(cmd_vel.theta) * sim_time_;
136 
137  // Pick the maximum of the two
138  int num_steps = ceil(
139  std::max(
140  projected_linear_distance / linear_granularity_,
141  projected_angular_distance / angular_granularity_));
142  steps.resize(num_steps);
143  }
144  if (steps.size() == 0) {
145  steps.resize(1);
146  }
147  std::fill(steps.begin(), steps.end(), sim_time_ / steps.size());
148  return steps;
149 }
150 
152  const geometry_msgs::msg::Pose2D & start_pose,
153  const nav_2d_msgs::msg::Twist2D & start_vel,
154  const nav_2d_msgs::msg::Twist2D & cmd_vel)
155 {
156  dwb_msgs::msg::Trajectory2D traj;
157  traj.velocity = cmd_vel;
158  // simulate the trajectory
159  geometry_msgs::msg::Pose2D pose = start_pose;
160  nav_2d_msgs::msg::Twist2D vel = start_vel;
161  double running_time = 0.0;
162  std::vector<double> steps = getTimeSteps(cmd_vel);
163  traj.poses.push_back(start_pose);
164  bool first_vel = false;
165  for (double dt : steps) {
166  // calculate velocities
167  vel = computeNewVelocity(cmd_vel, vel, dt);
168  if (!first_vel && limit_vel_cmd_in_traj_) {
169  traj.velocity = vel;
170  first_vel = true;
171  }
172 
173  // update the position of the robot using the velocities passed in
174  pose = computeNewPosition(pose, vel, dt);
175 
176  traj.poses.push_back(pose);
177  traj.time_offsets.push_back(rclcpp::Duration::from_seconds(running_time));
178  running_time += dt;
179  } // end for simulation steps
180 
181  if (include_last_point_) {
182  traj.poses.push_back(pose);
183  traj.time_offsets.push_back(rclcpp::Duration::from_seconds(running_time));
184  }
185 
186  return traj;
187 }
188 
193  const nav_2d_msgs::msg::Twist2D & cmd_vel,
194  const nav_2d_msgs::msg::Twist2D & start_vel, const double dt)
195 {
196  KinematicParameters kinematics = kinematics_handler_->getKinematics();
197  nav_2d_msgs::msg::Twist2D new_vel;
198  new_vel.x = projectVelocity(
199  start_vel.x, kinematics.getAccX(),
200  kinematics.getDecelX(), dt, cmd_vel.x);
201  new_vel.y = projectVelocity(
202  start_vel.y, kinematics.getAccY(),
203  kinematics.getDecelY(), dt, cmd_vel.y);
204  new_vel.theta = projectVelocity(
205  start_vel.theta,
206  kinematics.getAccTheta(), kinematics.getDecelTheta(),
207  dt, cmd_vel.theta);
208  return new_vel;
209 }
210 
212  const geometry_msgs::msg::Pose2D start_pose,
213  const nav_2d_msgs::msg::Twist2D & vel, const double dt)
214 {
215  geometry_msgs::msg::Pose2D new_pose;
216  new_pose.x = start_pose.x +
217  (vel.x * cos(start_pose.theta) + vel.y * cos(M_PI_2 + start_pose.theta)) * dt;
218  new_pose.y = start_pose.y +
219  (vel.x * sin(start_pose.theta) + vel.y * sin(M_PI_2 + start_pose.theta)) * dt;
220  new_pose.theta = start_pose.theta + vel.theta * dt;
221  return new_pose;
222 }
223 
224 } // namespace dwb_plugins
225 
226 PLUGINLIB_EXPORT_CLASS(
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...
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.
A struct containing one representation of the robot's kinematics.