Standard DWA-like trajectory generator.
More...
#include <standard_traj_generator.h>
|
virtual void | checkUseDwaParam (const ros::NodeHandle &nh) |
| Check if the deprecated use_dwa parameter is set to the functionality that matches this class. More...
|
|
virtual geometry_msgs::Pose2D | computeNewPosition (const geometry_msgs::Pose2D start_pose, const nav_2d_msgs::Twist2D &vel, const double dt) |
| Use the robot's kinematic model to predict new positions for the robot. More...
|
|
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. More...
|
|
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. More...
|
|
virtual void | initializeIterator (ros::NodeHandle &nh) |
| Initialize the VelocityIterator pointer. Put in its own function for easy overriding. More...
|
|
Standard DWA-like trajectory generator.
Definition at line 52 of file standard_traj_generator.h.
void dwb_plugins::StandardTrajectoryGenerator::checkUseDwaParam |
( |
const ros::NodeHandle & |
nh | ) |
|
|
protectedvirtual |
geometry_msgs::Pose2D dwb_plugins::StandardTrajectoryGenerator::computeNewPosition |
( |
const geometry_msgs::Pose2D |
start_pose, |
|
|
const nav_2d_msgs::Twist2D & |
vel, |
|
|
const double |
dt |
|
) |
| |
|
protectedvirtual |
Use the robot's kinematic model to predict new positions for the robot.
- Parameters
-
start_pose | Starting pose |
vel | Actual robot velocity (assumed to be within acceleration limits) |
dt | amount of time in seconds |
- Returns
- New pose after dt seconds
Definition at line 189 of file standard_traj_generator.cpp.
nav_2d_msgs::Twist2D dwb_plugins::StandardTrajectoryGenerator::computeNewVelocity |
( |
const nav_2d_msgs::Twist2D & |
cmd_vel, |
|
|
const nav_2d_msgs::Twist2D & |
start_vel, |
|
|
const double |
dt |
|
) |
| |
|
protectedvirtual |
Calculate the velocity after a set period of time, given the desired velocity and acceleration limits.
- Parameters
-
cmd_vel | Desired velocity |
start_vel | starting velocity |
dt | amount of time in seconds |
- Returns
- new velocity after dt seconds
change vel using acceleration limits to converge towards sample_target-vel
Reimplemented in dwb_plugins::LimitedAccelGenerator.
Definition at line 178 of file standard_traj_generator.cpp.
dwb_msgs::Trajectory2D dwb_plugins::StandardTrajectoryGenerator::generateTrajectory |
( |
const geometry_msgs::Pose2D & |
start_pose, |
|
|
const nav_2d_msgs::Twist2D & |
start_vel, |
|
|
const nav_2d_msgs::Twist2D & |
cmd_vel |
|
) |
| |
|
overridevirtual |
std::vector< double > dwb_plugins::StandardTrajectoryGenerator::getTimeSteps |
( |
const nav_2d_msgs::Twist2D & |
cmd_vel | ) |
|
|
protectedvirtual |
Compute an array of time deltas between the points in the generated trajectory.
- Parameters
-
cmd_vel | The desired command velocity |
- Returns
- vector of the difference between each time step in the generated trajectory
If we are discretizing by time, the returned vector will be the same constant time_granularity for all cmd_vels. Otherwise, you will get times based on the linear/angular granularity.
Right now the vector contains a single value repeated many times, but this method could be overridden to allow for dynamic spacing
Definition at line 112 of file standard_traj_generator.cpp.
bool dwb_plugins::StandardTrajectoryGenerator::hasMoreTwists |
( |
| ) |
|
|
overridevirtual |
void dwb_plugins::StandardTrajectoryGenerator::initialize |
( |
ros::NodeHandle & |
nh | ) |
|
|
overridevirtual |
void dwb_plugins::StandardTrajectoryGenerator::initializeIterator |
( |
ros::NodeHandle & |
nh | ) |
|
|
protectedvirtual |
nav_2d_msgs::Twist2D dwb_plugins::StandardTrajectoryGenerator::nextTwist |
( |
| ) |
|
|
overridevirtual |
void dwb_plugins::StandardTrajectoryGenerator::startNewIteration |
( |
const nav_2d_msgs::Twist2D & |
current_velocity | ) |
|
|
overridevirtual |
double dwb_plugins::StandardTrajectoryGenerator::angular_granularity_ |
|
protected |
bool dwb_plugins::StandardTrajectoryGenerator::discretize_by_time_ |
|
protected |
bool dwb_plugins::StandardTrajectoryGenerator::include_last_point_ |
|
protected |
double dwb_plugins::StandardTrajectoryGenerator::linear_granularity_ |
|
protected |
double dwb_plugins::StandardTrajectoryGenerator::sim_time_ |
|
protected |
double dwb_plugins::StandardTrajectoryGenerator::time_granularity_ |
|
protected |
std::shared_ptr<VelocityIterator> dwb_plugins::StandardTrajectoryGenerator::velocity_iterator_ |
|
protected |
The documentation for this class was generated from the following files: