Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
dwb_plugins::StandardTrajectoryGenerator Class Reference

Standard DWA-like trajectory generator. More...

#include <nav2_dwb_controller/dwb_plugins/include/dwb_plugins/standard_traj_generator.hpp>

Inheritance diagram for dwb_plugins::StandardTrajectoryGenerator:
Inheritance graph
[legend]
Collaboration diagram for dwb_plugins::StandardTrajectoryGenerator:
Collaboration graph
[legend]

Public Member Functions

void initialize (const nav2::LifecycleNode::SharedPtr &nh, const std::string &plugin_name) override
 Initialize parameters as needed. More...
 
void startNewIteration (const nav_2d_msgs::msg::Twist2D &current_velocity) override
 Start a new iteration based on the current velocity. More...
 
bool hasMoreTwists () override
 Test to see whether there are more twists to test. More...
 
nav_2d_msgs::msg::Twist2D nextTwist () override
 Return the next twist and advance the iteration. More...
 
dwb_msgs::msg::Trajectory2D generateTrajectory (const geometry_msgs::msg::Pose &start_pose, const nav_2d_msgs::msg::Twist2D &start_vel, const nav_2d_msgs::msg::Twist2D &cmd_vel) override
 Given a cmd_vel in the robot's frame and initial conditions, generate a Trajectory2D. More...
 
void setSpeedLimit (const double &speed_limit, const bool &percentage) override
 Limits the maximum linear speed of the robot. More...
 
- Public Member Functions inherited from dwb_core::TrajectoryGenerator
virtual void reset ()
 
virtual std::vector< nav_2d_msgs::msg::Twist2D > getTwists (const nav_2d_msgs::msg::Twist2D &current_velocity)
 Get all the twists for an iteration. More...
 

Protected Member Functions

virtual void initializeIterator (const nav2::LifecycleNode::SharedPtr &nh)
 Initialize the VelocityIterator pointer. Put in its own function for easy overriding.
 
virtual nav_2d_msgs::msg::Twist2D computeNewVelocity (const nav_2d_msgs::msg::Twist2D &cmd_vel, const nav_2d_msgs::msg::Twist2D &start_vel, const double dt)
 Calculate the velocity after a set period of time, given the desired velocity and acceleration limits. More...
 
virtual geometry_msgs::msg::Pose computeNewPosition (const geometry_msgs::msg::Pose start_pose, const nav_2d_msgs::msg::Twist2D &vel, const double dt)
 Use the robot's kinematic model to predict new positions for the robot. More...
 
virtual std::vector< double > getTimeSteps (const nav_2d_msgs::msg::Twist2D &cmd_vel)
 Compute an array of time deltas between the points in the generated trajectory. More...
 

Protected Attributes

KinematicsHandler::Ptr kinematics_handler_
 
std::shared_ptr< VelocityIteratorvelocity_iterator_
 
double sim_time_
 
bool discretize_by_time_
 
double time_granularity_
 If discretizing by time, the amount of time between each point in the traj.
 
double linear_granularity_
 If not discretizing by time, the amount of linear space between points.
 
double angular_granularity_
 If not discretizing by time, the amount of angular space between points.
 
std::string plugin_name_
 the name of the overlying plugin ID
 
bool limit_vel_cmd_in_traj_
 Option to limit velocity in the trajectory generator by using current velocity.
 
bool include_last_point_
 

Additional Inherited Members

- Public Types inherited from dwb_core::TrajectoryGenerator
typedef std::shared_ptr< dwb_core::TrajectoryGeneratorPtr
 

Detailed Description

Standard DWA-like trajectory generator.

Definition at line 55 of file standard_traj_generator.hpp.

Member Function Documentation

◆ computeNewPosition()

geometry_msgs::msg::Pose dwb_plugins::StandardTrajectoryGenerator::computeNewPosition ( const geometry_msgs::msg::Pose  start_pose,
const nav_2d_msgs::msg::Twist2D &  vel,
const double  dt 
)
protectedvirtual

Use the robot's kinematic model to predict new positions for the robot.

Parameters
start_poseStarting pose
velActual robot velocity (assumed to be within acceleration limits)
dtamount of time in seconds
Returns
New pose after dt seconds

Definition at line 212 of file standard_traj_generator.cpp.

Referenced by generateTrajectory().

Here is the caller graph for this function:

◆ computeNewVelocity()

nav_2d_msgs::msg::Twist2D dwb_plugins::StandardTrajectoryGenerator::computeNewVelocity ( const nav_2d_msgs::msg::Twist2D &  cmd_vel,
const nav_2d_msgs::msg::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_velDesired velocity
start_velstarting velocity
dtamount 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 193 of file standard_traj_generator.cpp.

Referenced by generateTrajectory().

Here is the caller graph for this function:

◆ generateTrajectory()

dwb_msgs::msg::Trajectory2D dwb_plugins::StandardTrajectoryGenerator::generateTrajectory ( const geometry_msgs::msg::Pose &  start_pose,
const nav_2d_msgs::msg::Twist2D &  start_vel,
const nav_2d_msgs::msg::Twist2D &  cmd_vel 
)
overridevirtual

Given a cmd_vel in the robot's frame and initial conditions, generate a Trajectory2D.

Parameters
start_poseCurrent robot location
start_velCurrent robot velocity
cmd_velThe desired command velocity

Implements dwb_core::TrajectoryGenerator.

Definition at line 152 of file standard_traj_generator.cpp.

References computeNewPosition(), computeNewVelocity(), getTimeSteps(), and limit_vel_cmd_in_traj_.

Here is the call graph for this function:

◆ getTimeSteps()

std::vector< double > dwb_plugins::StandardTrajectoryGenerator::getTimeSteps ( const nav_2d_msgs::msg::Twist2D &  cmd_vel)
protectedvirtual

Compute an array of time deltas between the points in the generated trajectory.

Parameters
cmd_velThe 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 123 of file standard_traj_generator.cpp.

References angular_granularity_, linear_granularity_, and time_granularity_.

Referenced by generateTrajectory().

Here is the caller graph for this function:

◆ hasMoreTwists()

bool dwb_plugins::StandardTrajectoryGenerator::hasMoreTwists ( )
overridevirtual

Test to see whether there are more twists to test.

Returns
True if more twists, false otherwise

Implements dwb_core::TrajectoryGenerator.

Definition at line 113 of file standard_traj_generator.cpp.

◆ initialize()

void dwb_plugins::StandardTrajectoryGenerator::initialize ( const nav2::LifecycleNode::SharedPtr &  nh,
const std::string &  plugin_name 
)
overridevirtual

Initialize parameters as needed.

Parameters
nhNodeHandle to read parameters from

Implements dwb_core::TrajectoryGenerator.

Definition at line 50 of file standard_traj_generator.cpp.

References angular_granularity_, initializeIterator(), limit_vel_cmd_in_traj_, linear_granularity_, plugin_name_, and time_granularity_.

Referenced by dwb_plugins::LimitedAccelGenerator::initialize().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ nextTwist()

nav_2d_msgs::msg::Twist2D dwb_plugins::StandardTrajectoryGenerator::nextTwist ( )
overridevirtual

Return the next twist and advance the iteration.

Returns
The Twist!

Implements dwb_core::TrajectoryGenerator.

Definition at line 118 of file standard_traj_generator.cpp.

◆ setSpeedLimit()

void dwb_plugins::StandardTrajectoryGenerator::setSpeedLimit ( const double &  speed_limit,
const bool &  percentage 
)
inlineoverridevirtual

Limits the maximum linear speed of the robot.

Parameters
speed_limitexpressed in absolute value (in m/s) or in percentage from maximum robot speed.
percentageSetting speed limit in percentage if true or in absolute values in false case.

Implements dwb_core::TrajectoryGenerator.

Definition at line 78 of file standard_traj_generator.hpp.

◆ startNewIteration()

void dwb_plugins::StandardTrajectoryGenerator::startNewIteration ( const nav_2d_msgs::msg::Twist2D &  current_velocity)
overridevirtual

Start a new iteration based on the current velocity.

Parameters
current_velocity

Implements dwb_core::TrajectoryGenerator.

Definition at line 107 of file standard_traj_generator.cpp.


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