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

Limits the acceleration in the generated trajectories to a fraction of the simulated time. More...

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

Inheritance diagram for dwb_plugins::LimitedAccelGenerator:
Inheritance graph
[legend]
Collaboration diagram for dwb_plugins::LimitedAccelGenerator:
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...
 
- Public Member Functions inherited from dwb_plugins::StandardTrajectoryGenerator
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

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) override
 Calculate the velocity after a set period of time, given the desired velocity and acceleration limits. More...
 
- Protected Member Functions inherited from dwb_plugins::StandardTrajectoryGenerator
virtual void initializeIterator (const nav2::LifecycleNode::SharedPtr &nh)
 Initialize the VelocityIterator pointer. Put in its own function for easy overriding.
 
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

double acceleration_time_
 
std::string plugin_name_
 
- Protected Attributes inherited from dwb_plugins::StandardTrajectoryGenerator
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

Limits the acceleration in the generated trajectories to a fraction of the simulated time.

Definition at line 50 of file limited_accel_generator.hpp.

Member Function Documentation

◆ computeNewVelocity()

nav_2d_msgs::msg::Twist2D dwb_plugins::LimitedAccelGenerator::computeNewVelocity ( const nav_2d_msgs::msg::Twist2D &  cmd_vel,
const nav_2d_msgs::msg::Twist2D &  start_vel,
const double  dt 
)
overrideprotectedvirtual

Calculate the velocity after a set period of time, given the desired velocity and acceleration limits.

Unlike the StandardTrajectoryGenerator, the velocity remains constant in the LimitedAccelGenerator

Parameters
cmd_velDesired velocity
start_velstarting velocity
dtamount of time in seconds
Returns
cmd_vel

Reimplemented from dwb_plugins::StandardTrajectoryGenerator.

Definition at line 86 of file limited_accel_generator.cpp.

◆ initialize()

void dwb_plugins::LimitedAccelGenerator::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 46 of file limited_accel_generator.cpp.

References dwb_plugins::StandardTrajectoryGenerator::initialize().

Here is the call graph for this function:

◆ startNewIteration()

void dwb_plugins::LimitedAccelGenerator::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 80 of file limited_accel_generator.cpp.


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