simple_trajectory_generator.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: TKruse
36  *********************************************************************/
37 
38 #ifndef SIMPLE_TRAJECTORY_GENERATOR_H_
39 #define SIMPLE_TRAJECTORY_GENERATOR_H_
40 
43 #include <Eigen/Core>
44 
45 namespace base_local_planner {
46 
62 public:
63 
65  limits_ = NULL;
66  }
67 
69 
79  void initialise(
80  const Eigen::Vector3f& pos,
81  const Eigen::Vector3f& vel,
82  const Eigen::Vector3f& goal,
84  const Eigen::Vector3f& vsamples,
85  std::vector<Eigen::Vector3f> additional_samples,
86  bool discretize_by_time = false);
87 
96  void initialise(
97  const Eigen::Vector3f& pos,
98  const Eigen::Vector3f& vel,
99  const Eigen::Vector3f& goal,
101  const Eigen::Vector3f& vsamples,
102  bool discretize_by_time = false);
103 
112  void setParameters(double sim_time,
113  double sim_granularity,
114  double angular_sim_granularity,
115  bool use_dwa = false,
116  double sim_period = 0.0);
117 
121  bool hasMoreTrajectories();
122 
126  bool nextTrajectory(Trajectory &traj);
127 
128 
129  static Eigen::Vector3f computeNewPositions(const Eigen::Vector3f& pos,
130  const Eigen::Vector3f& vel, double dt);
131 
132  static Eigen::Vector3f computeNewVelocities(const Eigen::Vector3f& sample_target_vel,
133  const Eigen::Vector3f& vel, Eigen::Vector3f acclimits, double dt);
134 
135  bool generateTrajectory(
136  Eigen::Vector3f pos,
137  Eigen::Vector3f vel,
138  Eigen::Vector3f sample_target_vel,
140 
141 protected:
142 
143  unsigned int next_sample_index_;
144  // to store sample params of each sample between init and generation
145  std::vector<Eigen::Vector3f> sample_params_;
147  Eigen::Vector3f pos_;
148  Eigen::Vector3f vel_;
149 
150  // whether velocity of trajectory changes over time or not
153 
155  bool use_dwa_;
156  double sim_period_; // only for dwa
157 };
158 
159 } /* namespace base_local_planner */
160 #endif /* SIMPLE_TRAJECTORY_GENERATOR_H_ */
void initialise(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, const Eigen::Vector3f &goal, base_local_planner::LocalPlannerLimits *limits, const Eigen::Vector3f &vsamples, std::vector< Eigen::Vector3f > additional_samples, bool discretize_by_time=false)
bool generateTrajectory(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f sample_target_vel, base_local_planner::Trajectory &traj)
static Eigen::Vector3f computeNewVelocities(const Eigen::Vector3f &sample_target_vel, const Eigen::Vector3f &vel, Eigen::Vector3f acclimits, double dt)
static Eigen::Vector3f computeNewPositions(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, double dt)
base_local_planner::LocalPlannerLimits * limits_
void setParameters(double sim_time, double sim_granularity, double angular_sim_granularity, bool use_dwa=false, double sim_period=0.0)
Provides an interface for navigation trajectory generators.
Holds a trajectory generated by considering an x, y, and theta velocity.
Definition: trajectory.h:44


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:25