35 #ifndef DWB_PLUGINS__STANDARD_TRAJ_GENERATOR_HPP_
36 #define DWB_PLUGINS__STANDARD_TRAJ_GENERATOR_HPP_
42 #include "rclcpp/rclcpp.hpp"
43 #include "dwb_core/trajectory_generator.hpp"
44 #include "dwb_plugins/velocity_iterator.hpp"
45 #include "dwb_plugins/kinematic_parameters.hpp"
46 #include "nav2_ros_common/lifecycle_node.hpp"
60 const nav2::LifecycleNode::SharedPtr & nh,
61 const std::string & plugin_name)
override;
62 void startNewIteration(
const nav_2d_msgs::msg::Twist2D & current_velocity)
override;
64 nav_2d_msgs::msg::Twist2D
nextTwist()
override;
67 const geometry_msgs::msg::Pose & start_pose,
68 const nav_2d_msgs::msg::Twist2D & start_vel,
69 const nav_2d_msgs::msg::Twist2D & cmd_vel)
override;
78 void setSpeedLimit(
const double & speed_limit,
const bool & percentage)
override
80 if (kinematics_handler_) {
81 kinematics_handler_->setSpeedLimit(speed_limit, percentage);
100 const nav_2d_msgs::msg::Twist2D & cmd_vel,
const nav_2d_msgs::msg::Twist2D & start_vel,
112 const geometry_msgs::msg::Pose start_pose,
const nav_2d_msgs::msg::Twist2D & vel,
128 virtual std::vector<double>
getTimeSteps(
const nav_2d_msgs::msg::Twist2D & cmd_vel);
130 KinematicsHandler::Ptr kinematics_handler_;
131 std::shared_ptr<VelocityIterator> velocity_iterator_;
136 bool discretize_by_time_;
166 bool include_last_point_;
Interface for iterating through possible velocities and creating trajectories.
Standard DWA-like trajectory generator.
void startNewIteration(const nav_2d_msgs::msg::Twist2D ¤t_velocity) override
Start a new iteration based on the current velocity.
double angular_granularity_
If not discretizing by time, the amount of angular space between points.
virtual 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)
Calculate the velocity after a set period of time, given the desired velocity and acceleration limits...
void setSpeedLimit(const double &speed_limit, const bool &percentage) override
Limits the maximum linear speed of the robot.
std::string plugin_name_
the name of the overlying plugin ID
bool hasMoreTwists() override
Test to see whether there are more twists to test.
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.
bool limit_vel_cmd_in_traj_
Option to limit velocity in the trajectory generator by using current velocity.
double linear_granularity_
If not discretizing by time, the amount of linear space between points.
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.
double time_granularity_
If discretizing by time, the amount of time between each point in the traj.
void initialize(const nav2::LifecycleNode::SharedPtr &nh, const std::string &plugin_name) override
Initialize parameters as needed.
virtual void initializeIterator(const nav2::LifecycleNode::SharedPtr &nh)
Initialize the VelocityIterator pointer. Put in its own function for easy overriding.
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.
nav_2d_msgs::msg::Twist2D nextTwist() override
Return the next twist and advance the iteration.