35 #ifndef DWB_LOCAL_PLANNER_TRAJECTORY_GENERATOR_H 36 #define DWB_LOCAL_PLANNER_TRAJECTORY_GENERATOR_H 39 #include <nav_2d_msgs/Twist2D.h> 40 #include <dwb_msgs/Trajectory2D.h> 64 using Ptr = std::shared_ptr<dwb_local_planner::TrajectoryGenerator>;
95 virtual nav_2d_msgs::Twist2D
nextTwist() = 0;
105 virtual std::vector<nav_2d_msgs::Twist2D>
getTwists(
const nav_2d_msgs::Twist2D& current_velocity)
107 std::vector<nav_2d_msgs::Twist2D> twists;
122 virtual dwb_msgs::Trajectory2D
generateTrajectory(
const geometry_msgs::Pose2D& start_pose,
123 const nav_2d_msgs::Twist2D& start_vel,
124 const nav_2d_msgs::Twist2D& cmd_vel) = 0;
129 #endif // DWB_LOCAL_PLANNER_TRAJECTORY_GENERATOR_H virtual ~TrajectoryGenerator()
virtual void startNewIteration(const nav_2d_msgs::Twist2D ¤t_velocity)=0
Start a new iteration based on the current velocity.
virtual void reset()
Reset the state (if any) when the planner gets a new goal.
virtual void initialize(ros::NodeHandle &nh)=0
Initialize parameters as needed.
virtual dwb_msgs::Trajectory2D generateTrajectory(const geometry_msgs::Pose2D &start_pose, const nav_2d_msgs::Twist2D &start_vel, const nav_2d_msgs::Twist2D &cmd_vel)=0
Given a cmd_vel in the robot's frame and initial conditions, generate a Trajectory2D.
virtual nav_2d_msgs::Twist2D nextTwist()=0
Return the next twist and advance the iteration.
std::shared_ptr< dwb_local_planner::TrajectoryGenerator > Ptr
virtual bool hasMoreTwists()=0
Test to see whether there are more twists to test.
Interface for iterating through possible velocities and creating trajectories.
virtual std::vector< nav_2d_msgs::Twist2D > getTwists(const nav_2d_msgs::Twist2D ¤t_velocity)
Get all the twists for an iteration.