35 #ifndef DWB_CORE__TRAJECTORY_GENERATOR_HPP_
36 #define DWB_CORE__TRAJECTORY_GENERATOR_HPP_
41 #include "rclcpp/rclcpp.hpp"
42 #include "nav_2d_msgs/msg/twist2_d.hpp"
43 #include "dwb_msgs/msg/trajectory2_d.hpp"
44 #include "nav2_ros_common/lifecycle_node.hpp"
67 typedef std::shared_ptr<dwb_core::TrajectoryGenerator> Ptr;
76 const nav2::LifecycleNode::SharedPtr & nh,
77 const std::string & plugin_name) = 0;
78 virtual void reset() {}
105 virtual std::vector<nav_2d_msgs::msg::Twist2D>
getTwists(
106 const nav_2d_msgs::msg::Twist2D & current_velocity)
108 std::vector<nav_2d_msgs::msg::Twist2D> twists;
123 const geometry_msgs::msg::Pose & start_pose,
124 const nav_2d_msgs::msg::Twist2D & start_vel,
125 const nav_2d_msgs::msg::Twist2D & cmd_vel) = 0;
134 virtual void setSpeedLimit(
const double & speed_limit,
const bool & percentage) = 0;
Interface for iterating through possible velocities and creating trajectories.
virtual void initialize(const nav2::LifecycleNode::SharedPtr &nh, const std::string &plugin_name)=0
Initialize parameters as needed.
virtual 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)=0
Given a cmd_vel in the robot's frame and initial conditions, generate a Trajectory2D.
virtual nav_2d_msgs::msg::Twist2D nextTwist()=0
Return the next twist and advance the iteration.
virtual std::vector< nav_2d_msgs::msg::Twist2D > getTwists(const nav_2d_msgs::msg::Twist2D ¤t_velocity)
Get all the twists for an iteration.
virtual bool hasMoreTwists()=0
Test to see whether there are more twists to test.
virtual void startNewIteration(const nav_2d_msgs::msg::Twist2D ¤t_velocity)=0
Start a new iteration based on the current velocity.
virtual void setSpeedLimit(const double &speed_limit, const bool &percentage)=0
Limits the maximum linear speed of the robot.