00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2017, Locus Robotics 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the copyright holder nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 */ 00034 00035 #ifndef DWB_PLUGINS_STANDARD_TRAJ_GENERATOR_H 00036 #define DWB_PLUGINS_STANDARD_TRAJ_GENERATOR_H 00037 00038 #include <ros/ros.h> 00039 #include <dwb_local_planner/trajectory_generator.h> 00040 #include <dwb_plugins/velocity_iterator.h> 00041 #include <dwb_plugins/kinematic_parameters.h> 00042 #include <vector> 00043 #include <memory> 00044 00045 namespace dwb_plugins 00046 { 00047 00052 class StandardTrajectoryGenerator : public dwb_local_planner::TrajectoryGenerator 00053 { 00054 public: 00055 // Standard TrajectoryGenerator interface 00056 void initialize(ros::NodeHandle& nh) override; 00057 void startNewIteration(const nav_2d_msgs::Twist2D& current_velocity) override; 00058 bool hasMoreTwists() override; 00059 nav_2d_msgs::Twist2D nextTwist() override; 00060 00061 dwb_msgs::Trajectory2D generateTrajectory(const geometry_msgs::Pose2D& start_pose, 00062 const nav_2d_msgs::Twist2D& start_vel, 00063 const nav_2d_msgs::Twist2D& cmd_vel) override; 00064 protected: 00068 virtual void initializeIterator(ros::NodeHandle& nh); 00069 00077 virtual void checkUseDwaParam(const ros::NodeHandle& nh); 00078 00087 virtual nav_2d_msgs::Twist2D computeNewVelocity(const nav_2d_msgs::Twist2D& cmd_vel, 00088 const nav_2d_msgs::Twist2D& start_vel, 00089 const double dt); 00090 00099 virtual geometry_msgs::Pose2D computeNewPosition(const geometry_msgs::Pose2D start_pose, 00100 const nav_2d_msgs::Twist2D& vel, 00101 const double dt); 00102 00103 00116 virtual std::vector<double> getTimeSteps(const nav_2d_msgs::Twist2D& cmd_vel); 00117 00118 KinematicParameters::Ptr kinematics_; 00119 std::shared_ptr<VelocityIterator> velocity_iterator_; 00120 00121 double sim_time_; 00122 00123 // Sampling Parameters 00124 bool discretize_by_time_; 00125 double time_granularity_; 00126 double linear_granularity_; 00127 double angular_granularity_; 00128 00129 /* Backwards Compatibility Parameter: include_last_point 00130 * 00131 * dwa had an off-by-one error built into it. 00132 * It generated N trajectory points, where N = ceil(sim_time / time_delta). 00133 * If for example, sim_time=3.0 and time_delta=1.5, it would generate trajectories with 2 points, which 00134 * indeed were time_delta seconds apart. However, the points would be at t=0 and t=1.5, and thus the 00135 * actual sim_time was much less than advertised. 00136 * 00137 * This is remedied by adding one final point at t=sim_time, but only if include_last_point_ is true. 00138 * 00139 * Nothing I could find actually used the time_delta variable or seemed to care that the trajectories 00140 * were not projected out as far as they intended. 00141 */ 00142 bool include_last_point_; 00143 }; 00144 00145 00146 } // namespace dwb_plugins 00147 00148 #endif // DWB_PLUGINS_STANDARD_TRAJ_GENERATOR_H