35 #ifndef DWB_PLUGINS_STANDARD_TRAJ_GENERATOR_H 36 #define DWB_PLUGINS_STANDARD_TRAJ_GENERATOR_H 59 nav_2d_msgs::Twist2D
nextTwist()
override;
62 const nav_2d_msgs::Twist2D& start_vel,
63 const nav_2d_msgs::Twist2D& cmd_vel)
override;
88 const nav_2d_msgs::Twist2D& start_vel,
99 virtual geometry_msgs::Pose2D
computeNewPosition(
const geometry_msgs::Pose2D start_pose,
100 const nav_2d_msgs::Twist2D& vel,
116 virtual std::vector<double>
getTimeSteps(
const nav_2d_msgs::Twist2D& cmd_vel);
148 #endif // DWB_PLUGINS_STANDARD_TRAJ_GENERATOR_H
dwb_msgs::Trajectory2D generateTrajectory(const geometry_msgs::Pose2D &start_pose, const nav_2d_msgs::Twist2D &start_vel, const nav_2d_msgs::Twist2D &cmd_vel) override
virtual nav_2d_msgs::Twist2D computeNewVelocity(const nav_2d_msgs::Twist2D &cmd_vel, const nav_2d_msgs::Twist2D &start_vel, const double dt)
Calculate the velocity after a set period of time, given the desired velocity and acceleration limits...
virtual std::vector< double > getTimeSteps(const nav_2d_msgs::Twist2D &cmd_vel)
Compute an array of time deltas between the points in the generated trajectory.
std::shared_ptr< KinematicParameters > Ptr
virtual void initializeIterator(ros::NodeHandle &nh)
Initialize the VelocityIterator pointer. Put in its own function for easy overriding.
void startNewIteration(const nav_2d_msgs::Twist2D ¤t_velocity) override
bool hasMoreTwists() override
Standard DWA-like trajectory generator.
virtual geometry_msgs::Pose2D computeNewPosition(const geometry_msgs::Pose2D start_pose, const nav_2d_msgs::Twist2D &vel, const double dt)
Use the robot's kinematic model to predict new positions for the robot.
KinematicParameters::Ptr kinematics_
nav_2d_msgs::Twist2D nextTwist() override
virtual void checkUseDwaParam(const ros::NodeHandle &nh)
Check if the deprecated use_dwa parameter is set to the functionality that matches this class...
std::shared_ptr< VelocityIterator > velocity_iterator_
double angular_granularity_
If not discretizing by time, the amount of angular space between points.
double linear_granularity_
If not discretizing by time, the amount of linear space between points.
void initialize(ros::NodeHandle &nh) override
double time_granularity_
If discretizing by time, the amount of time between each point in the traj.