standard_traj_generator.h
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 
35 #ifndef DWB_PLUGINS_STANDARD_TRAJ_GENERATOR_H
36 #define DWB_PLUGINS_STANDARD_TRAJ_GENERATOR_H
37 
38 #include <ros/ros.h>
42 #include <vector>
43 #include <memory>
44 
45 namespace dwb_plugins
46 {
47 
53 {
54 public:
55  // Standard TrajectoryGenerator interface
56  void initialize(ros::NodeHandle& nh) override;
57  void startNewIteration(const nav_2d_msgs::Twist2D& current_velocity) override;
58  bool hasMoreTwists() override;
59  nav_2d_msgs::Twist2D nextTwist() override;
60 
61  dwb_msgs::Trajectory2D generateTrajectory(const geometry_msgs::Pose2D& start_pose,
62  const nav_2d_msgs::Twist2D& start_vel,
63  const nav_2d_msgs::Twist2D& cmd_vel) override;
64 protected:
68  virtual void initializeIterator(ros::NodeHandle& nh);
69 
77  virtual void checkUseDwaParam(const ros::NodeHandle& nh);
78 
87  virtual nav_2d_msgs::Twist2D computeNewVelocity(const nav_2d_msgs::Twist2D& cmd_vel,
88  const nav_2d_msgs::Twist2D& start_vel,
89  const double dt);
90 
99  virtual geometry_msgs::Pose2D computeNewPosition(const geometry_msgs::Pose2D start_pose,
100  const nav_2d_msgs::Twist2D& vel,
101  const double dt);
102 
103 
116  virtual std::vector<double> getTimeSteps(const nav_2d_msgs::Twist2D& cmd_vel);
117 
119  std::shared_ptr<VelocityIterator> velocity_iterator_;
120 
121  double sim_time_;
122 
123  // Sampling Parameters
128 
129  /* Backwards Compatibility Parameter: include_last_point
130  *
131  * dwa had an off-by-one error built into it.
132  * It generated N trajectory points, where N = ceil(sim_time / time_delta).
133  * If for example, sim_time=3.0 and time_delta=1.5, it would generate trajectories with 2 points, which
134  * indeed were time_delta seconds apart. However, the points would be at t=0 and t=1.5, and thus the
135  * actual sim_time was much less than advertised.
136  *
137  * This is remedied by adding one final point at t=sim_time, but only if include_last_point_ is true.
138  *
139  * Nothing I could find actually used the time_delta variable or seemed to care that the trajectories
140  * were not projected out as far as they intended.
141  */
143 };
144 
145 
146 } // namespace dwb_plugins
147 
148 #endif // DWB_PLUGINS_STANDARD_TRAJ_GENERATOR_H
dwb_msgs::Trajectory2D generateTrajectory(const geometry_msgs::Pose2D &start_pose, const nav_2d_msgs::Twist2D &start_vel, const nav_2d_msgs::Twist2D &cmd_vel) override
virtual nav_2d_msgs::Twist2D computeNewVelocity(const nav_2d_msgs::Twist2D &cmd_vel, const nav_2d_msgs::Twist2D &start_vel, const double dt)
Calculate the velocity after a set period of time, given the desired velocity and acceleration limits...
virtual std::vector< double > getTimeSteps(const nav_2d_msgs::Twist2D &cmd_vel)
Compute an array of time deltas between the points in the generated trajectory.
std::shared_ptr< KinematicParameters > Ptr
virtual void initializeIterator(ros::NodeHandle &nh)
Initialize the VelocityIterator pointer. Put in its own function for easy overriding.
void startNewIteration(const nav_2d_msgs::Twist2D &current_velocity) override
Standard DWA-like trajectory generator.
virtual geometry_msgs::Pose2D computeNewPosition(const geometry_msgs::Pose2D start_pose, const nav_2d_msgs::Twist2D &vel, const double dt)
Use the robot&#39;s kinematic model to predict new positions for the robot.
virtual void checkUseDwaParam(const ros::NodeHandle &nh)
Check if the deprecated use_dwa parameter is set to the functionality that matches this class...
std::shared_ptr< VelocityIterator > velocity_iterator_
double angular_granularity_
If not discretizing by time, the amount of angular space between points.
double linear_granularity_
If not discretizing by time, the amount of linear space between points.
void initialize(ros::NodeHandle &nh) override
double time_granularity_
If discretizing by time, the amount of time between each point in the traj.


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