Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef DWB_LOCAL_PLANNER_TRAJECTORY_GENERATOR_H
00036 #define DWB_LOCAL_PLANNER_TRAJECTORY_GENERATOR_H
00037
00038 #include <ros/ros.h>
00039 #include <nav_2d_msgs/Twist2D.h>
00040 #include <dwb_msgs/Trajectory2D.h>
00041 #include <vector>
00042
00043 namespace dwb_local_planner
00044 {
00045
00061 class TrajectoryGenerator
00062 {
00063 public:
00064 using Ptr = std::shared_ptr<dwb_local_planner::TrajectoryGenerator>;
00065
00066 virtual ~TrajectoryGenerator() {}
00067
00072 virtual void initialize(ros::NodeHandle& nh) = 0;
00073
00077 virtual void reset() {}
00078
00083 virtual void startNewIteration(const nav_2d_msgs::Twist2D& current_velocity) = 0;
00084
00089 virtual bool hasMoreTwists() = 0;
00090
00095 virtual nav_2d_msgs::Twist2D nextTwist() = 0;
00096
00105 virtual std::vector<nav_2d_msgs::Twist2D> getTwists(const nav_2d_msgs::Twist2D& current_velocity)
00106 {
00107 std::vector<nav_2d_msgs::Twist2D> twists;
00108 startNewIteration(current_velocity);
00109 while (hasMoreTwists())
00110 {
00111 twists.push_back(nextTwist());
00112 }
00113 return twists;
00114 }
00115
00122 virtual dwb_msgs::Trajectory2D generateTrajectory(const geometry_msgs::Pose2D& start_pose,
00123 const nav_2d_msgs::Twist2D& start_vel,
00124 const nav_2d_msgs::Twist2D& cmd_vel) = 0;
00125 };
00126
00127 }
00128
00129 #endif // DWB_LOCAL_PLANNER_TRAJECTORY_GENERATOR_H