Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
base_local_planner::SimpleTrajectoryGenerator Class Reference

#include <simple_trajectory_generator.h>

Inheritance diagram for base_local_planner::SimpleTrajectoryGenerator:
Inheritance graph
[legend]

Public Member Functions

bool generateTrajectory (Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f sample_target_vel, base_local_planner::Trajectory &traj)
 
bool hasMoreTrajectories ()
 
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)
 
void initialise (const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, const Eigen::Vector3f &goal, base_local_planner::LocalPlannerLimits *limits, const Eigen::Vector3f &vsamples, bool discretize_by_time=false)
 
bool nextTrajectory (Trajectory &traj)
 
void setParameters (double sim_time, double sim_granularity, double angular_sim_granularity, bool use_dwa=false, double sim_period=0.0)
 
 SimpleTrajectoryGenerator ()
 
 ~SimpleTrajectoryGenerator ()
 
- Public Member Functions inherited from base_local_planner::TrajectorySampleGenerator
virtual ~TrajectorySampleGenerator ()
 Virtual destructor for the interface. More...
 

Static Public Member Functions

static Eigen::Vector3f computeNewPositions (const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, double dt)
 
static Eigen::Vector3f computeNewVelocities (const Eigen::Vector3f &sample_target_vel, const Eigen::Vector3f &vel, Eigen::Vector3f acclimits, double dt)
 

Protected Attributes

double angular_sim_granularity_
 
bool continued_acceleration_
 
bool discretize_by_time_
 
base_local_planner::LocalPlannerLimitslimits_
 
unsigned int next_sample_index_
 
Eigen::Vector3f pos_
 
std::vector< Eigen::Vector3f > sample_params_
 
double sim_granularity_
 
double sim_period_
 
double sim_time_
 
bool use_dwa_
 
Eigen::Vector3f vel_
 

Additional Inherited Members

- Protected Member Functions inherited from base_local_planner::TrajectorySampleGenerator
 TrajectorySampleGenerator ()
 

Detailed Description

generates trajectories based on equi-distant discretisation of the degrees of freedom. This is supposed to be a simple and robust implementation of the TrajectorySampleGenerator interface, more efficient implementations are thinkable.

This can be used for both dwa and trajectory rollout approaches. As an example, assuming these values: sim_time = 1s, sim_period=200ms, dt = 200ms, vsamples_x=5, acc_limit_x = 1m/s^2, vel_x=0 (robot at rest, values just for easy calculations) dwa_planner will sample max-x-velocities from 0m/s to 0.2m/s. trajectory rollout approach will sample max-x-velocities 0m/s up to 1m/s trajectory rollout approach does so respecting the acceleration limit, so it gradually increases velocity

Definition at line 61 of file simple_trajectory_generator.h.

Constructor & Destructor Documentation

base_local_planner::SimpleTrajectoryGenerator::SimpleTrajectoryGenerator ( )
inline

Definition at line 64 of file simple_trajectory_generator.h.

base_local_planner::SimpleTrajectoryGenerator::~SimpleTrajectoryGenerator ( )
inline

Definition at line 68 of file simple_trajectory_generator.h.

Member Function Documentation

Eigen::Vector3f base_local_planner::SimpleTrajectoryGenerator::computeNewPositions ( const Eigen::Vector3f &  pos,
const Eigen::Vector3f &  vel,
double  dt 
)
static

Definition at line 253 of file simple_trajectory_generator.cpp.

Eigen::Vector3f base_local_planner::SimpleTrajectoryGenerator::computeNewVelocities ( const Eigen::Vector3f &  sample_target_vel,
const Eigen::Vector3f &  vel,
Eigen::Vector3f  acclimits,
double  dt 
)
static

change vel using acceleration limits to converge towards sample_target-vel

Definition at line 265 of file simple_trajectory_generator.cpp.

bool base_local_planner::SimpleTrajectoryGenerator::generateTrajectory ( Eigen::Vector3f  pos,
Eigen::Vector3f  vel,
Eigen::Vector3f  sample_target_vel,
base_local_planner::Trajectory traj 
)
Parameters
poscurrent position of robot
veldesired velocity for sampling

Definition at line 180 of file simple_trajectory_generator.cpp.

bool base_local_planner::SimpleTrajectoryGenerator::hasMoreTrajectories ( )
virtual

Whether this generator can create more trajectories

Implements base_local_planner::TrajectorySampleGenerator.

Definition at line 154 of file simple_trajectory_generator.cpp.

void base_local_planner::SimpleTrajectoryGenerator::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 
)
Parameters
poscurrent robot position
velcurrent robot velocity
limitsCurrent velocity limits
vsamplesin how many samples to divide the given dimension
use_acceleration_limitsif true use physical model, else idealized robot model
additional_samples(deprecated): Additional velocity samples to generate individual trajectories from.
discretize_by_timeif true, the trajectory is split according in chunks of the same duration, else of same length

Definition at line 46 of file simple_trajectory_generator.cpp.

void base_local_planner::SimpleTrajectoryGenerator::initialise ( const Eigen::Vector3f &  pos,
const Eigen::Vector3f &  vel,
const Eigen::Vector3f &  goal,
base_local_planner::LocalPlannerLimits limits,
const Eigen::Vector3f &  vsamples,
bool  discretize_by_time = false 
)
Parameters
poscurrent robot position
velcurrent robot velocity
limitsCurrent velocity limits
vsamplesin how many samples to divide the given dimension
use_acceleration_limitsif true use physical model, else idealized robot model
discretize_by_timeif true, the trajectory is split according in chunks of the same duration, else of same length

Definition at line 60 of file simple_trajectory_generator.cpp.

bool base_local_planner::SimpleTrajectoryGenerator::nextTrajectory ( Trajectory comp_traj)
virtual

Whether this generator can create more trajectories

Create and return the next sample trajectory

Implements base_local_planner::TrajectorySampleGenerator.

Definition at line 161 of file simple_trajectory_generator.cpp.

void base_local_planner::SimpleTrajectoryGenerator::setParameters ( double  sim_time,
double  sim_granularity,
double  angular_sim_granularity,
bool  use_dwa = false,
double  sim_period = 0.0 
)

This function is to be called only when parameters change

Parameters
sim_granularitygranularity of collision detection
angular_sim_granularityangular granularity of collision detection
use_dwawhether to use DWA or trajectory rollout
sim_perioddistance between points in one trajectory

Definition at line 137 of file simple_trajectory_generator.cpp.

Member Data Documentation

double base_local_planner::SimpleTrajectoryGenerator::angular_sim_granularity_
protected

Definition at line 154 of file simple_trajectory_generator.h.

bool base_local_planner::SimpleTrajectoryGenerator::continued_acceleration_
protected

Definition at line 151 of file simple_trajectory_generator.h.

bool base_local_planner::SimpleTrajectoryGenerator::discretize_by_time_
protected

Definition at line 152 of file simple_trajectory_generator.h.

base_local_planner::LocalPlannerLimits* base_local_planner::SimpleTrajectoryGenerator::limits_
protected

Definition at line 146 of file simple_trajectory_generator.h.

unsigned int base_local_planner::SimpleTrajectoryGenerator::next_sample_index_
protected

Definition at line 143 of file simple_trajectory_generator.h.

Eigen::Vector3f base_local_planner::SimpleTrajectoryGenerator::pos_
protected

Definition at line 147 of file simple_trajectory_generator.h.

std::vector<Eigen::Vector3f> base_local_planner::SimpleTrajectoryGenerator::sample_params_
protected

Definition at line 145 of file simple_trajectory_generator.h.

double base_local_planner::SimpleTrajectoryGenerator::sim_granularity_
protected

Definition at line 154 of file simple_trajectory_generator.h.

double base_local_planner::SimpleTrajectoryGenerator::sim_period_
protected

Definition at line 156 of file simple_trajectory_generator.h.

double base_local_planner::SimpleTrajectoryGenerator::sim_time_
protected

Definition at line 154 of file simple_trajectory_generator.h.

bool base_local_planner::SimpleTrajectoryGenerator::use_dwa_
protected

Definition at line 155 of file simple_trajectory_generator.h.

Eigen::Vector3f base_local_planner::SimpleTrajectoryGenerator::vel_
protected

Definition at line 148 of file simple_trajectory_generator.h.


The documentation for this class was generated from the following files:


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:49