Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
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>
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 ¤t_velocity) override |
Start a new iteration based on the current velocity. More... | |
![]() | |
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 ¤t_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... | |
![]() | |
virtual void | reset () |
virtual std::vector< nav_2d_msgs::msg::Twist2D > | getTwists (const nav_2d_msgs::msg::Twist2D ¤t_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... | |
![]() | |
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_ |
![]() | |
KinematicsHandler::Ptr | kinematics_handler_ |
std::shared_ptr< VelocityIterator > | velocity_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 | |
![]() | |
typedef std::shared_ptr< dwb_core::TrajectoryGenerator > | Ptr |
Limits the acceleration in the generated trajectories to a fraction of the simulated time.
Definition at line 50 of file limited_accel_generator.hpp.
|
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
cmd_vel | Desired velocity |
start_vel | starting velocity |
dt | amount of time in seconds |
Reimplemented from dwb_plugins::StandardTrajectoryGenerator.
Definition at line 86 of file limited_accel_generator.cpp.
|
overridevirtual |
Initialize parameters as needed.
nh | NodeHandle to read parameters from |
Implements dwb_core::TrajectoryGenerator.
Definition at line 46 of file limited_accel_generator.cpp.
References dwb_plugins::StandardTrajectoryGenerator::initialize().
|
overridevirtual |
Start a new iteration based on the current velocity.
current_velocity |
Implements dwb_core::TrajectoryGenerator.
Definition at line 80 of file limited_accel_generator.cpp.