Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
Interface for iterating through possible velocities and creating trajectories. More...
#include <nav2_dwb_controller/dwb_core/include/dwb_core/trajectory_generator.hpp>
Public Types | |
typedef std::shared_ptr< dwb_core::TrajectoryGenerator > | Ptr |
Public Member Functions | |
virtual void | initialize (const nav2_util::LifecycleNode::SharedPtr &nh, const std::string &plugin_name)=0 |
Initialize parameters as needed. More... | |
virtual void | reset () |
virtual void | startNewIteration (const nav_2d_msgs::msg::Twist2D ¤t_velocity)=0 |
Start a new iteration based on the current velocity. More... | |
virtual bool | hasMoreTwists ()=0 |
Test to see whether there are more twists to test. More... | |
virtual nav_2d_msgs::msg::Twist2D | nextTwist ()=0 |
Return the next twist and advance the iteration. More... | |
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... | |
virtual dwb_msgs::msg::Trajectory2D | generateTrajectory (const geometry_msgs::msg::Pose2D &start_pose, const nav_2d_msgs::msg::Twist2D &start_vel, const nav_2d_msgs::msg::Twist2D &cmd_vel)=0 |
Given a cmd_vel in the robot's frame and initial conditions, generate a Trajectory2D. More... | |
virtual void | setSpeedLimit (const double &speed_limit, const bool &percentage)=0 |
Limits the maximum linear speed of the robot. More... | |
Interface for iterating through possible velocities and creating trajectories.
This class defines the plugin interface for two separate but related components.
First, this class provides an iterator interface for exploring all of the velocities to search, given the current velocity.
Second, the class gives an independent interface for creating a trajectory from a twist, i.e. projecting it out in time and space.
Both components rely heavily on the robot's kinematic model, and can share many parameters, which is why they are grouped into a singular class.
Definition at line 64 of file trajectory_generator.hpp.
|
pure virtual |
Given a cmd_vel in the robot's frame and initial conditions, generate a Trajectory2D.
start_pose | Current robot location |
start_vel | Current robot velocity |
cmd_vel | The desired command velocity |
Implemented in dwb_plugins::StandardTrajectoryGenerator.
|
inlinevirtual |
Get all the twists for an iteration.
Note: Resets the iterator if one is in process
current_velocity |
Definition at line 105 of file trajectory_generator.hpp.
References hasMoreTwists(), nextTwist(), and startNewIteration().
|
pure virtual |
Test to see whether there are more twists to test.
Implemented in dwb_plugins::StandardTrajectoryGenerator.
Referenced by getTwists().
|
pure virtual |
Initialize parameters as needed.
nh | NodeHandle to read parameters from |
Implemented in dwb_plugins::StandardTrajectoryGenerator, and dwb_plugins::LimitedAccelGenerator.
|
pure virtual |
Return the next twist and advance the iteration.
Implemented in dwb_plugins::StandardTrajectoryGenerator.
Referenced by getTwists().
|
pure virtual |
Limits the maximum linear speed of the robot.
speed_limit | expressed in absolute value (in m/s) or in percentage from maximum robot speed. |
percentage | Setting speed limit in percentage if true or in absolute values in false case. |
Implemented in dwb_plugins::StandardTrajectoryGenerator.
|
pure virtual |
Start a new iteration based on the current velocity.
current_velocity |
Implemented in dwb_plugins::StandardTrajectoryGenerator, and dwb_plugins::LimitedAccelGenerator.
Referenced by getTwists().