38 #ifndef SIMPLE_TRAJECTORY_GENERATOR_H_ 39 #define SIMPLE_TRAJECTORY_GENERATOR_H_ 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);
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);
113 double sim_granularity,
114 double angular_sim_granularity,
115 bool use_dwa =
false,
116 double sim_period = 0.0);
130 const Eigen::Vector3f& vel,
double dt);
133 const Eigen::Vector3f& vel, Eigen::Vector3f acclimits,
double dt);
138 Eigen::Vector3f sample_target_vel,
SimpleTrajectoryGenerator()
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)
bool hasMoreTrajectories()
static Eigen::Vector3f computeNewVelocities(const Eigen::Vector3f &sample_target_vel, const Eigen::Vector3f &vel, Eigen::Vector3f acclimits, double dt)
double angular_sim_granularity_
bool nextTrajectory(Trajectory &traj)
static Eigen::Vector3f computeNewPositions(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, double dt)
std::vector< Eigen::Vector3f > sample_params_
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)
~SimpleTrajectoryGenerator()
Provides an interface for navigation trajectory generators.
unsigned int next_sample_index_
bool continued_acceleration_
Holds a trajectory generated by considering an x, y, and theta velocity.