51   kinematics_ = std::make_shared<KinematicParameters>();
    89   nh.
param(
"use_dwa", use_dwa, 
false);
    93                                       "Please use LimitedAccelGenerator for that functionality.");
   114   std::vector<double> steps;
   121     double vmag = hypot(cmd_vel.x, cmd_vel.y);
   124     double projected_linear_distance = vmag * 
sim_time_;
   127     double projected_angular_distance = fabs(cmd_vel.theta) * 
sim_time_;
   132     steps.resize(num_steps);
   134   if (steps.size() == 0)
   138   std::fill(steps.begin(), steps.end(), 
sim_time_ / steps.size());
   143     const nav_2d_msgs::Twist2D& start_vel,
   144     const nav_2d_msgs::Twist2D& cmd_vel)
   146   dwb_msgs::Trajectory2D traj;
   147   traj.velocity = cmd_vel;
   150   geometry_msgs::Pose2D pose = start_pose;
   151   nav_2d_msgs::Twist2D vel = start_vel;
   152   double running_time = 0.0;
   154   for (
double dt : steps)
   156     traj.poses.push_back(pose);
   168     traj.poses.push_back(pose);
   179     const nav_2d_msgs::Twist2D& start_vel, 
const double dt)
   181   nav_2d_msgs::Twist2D new_vel;
   190                                                                       const nav_2d_msgs::Twist2D& vel, 
const double dt)
   192   geometry_msgs::Pose2D new_pose;
   193   new_pose.x = start_pose.x + (vel.x * cos(start_pose.theta) + vel.y * cos(M_PI_2 + start_pose.theta)) * dt;
   194   new_pose.y = start_pose.y + (vel.x * sin(start_pose.theta) + vel.y * sin(M_PI_2 + start_pose.theta)) * dt;
   195   new_pose.theta = start_pose.theta + vel.theta * dt;
 
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. 
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. 
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
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. 
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
double projectVelocity(double v0, double accel, double decel, double dt, double target)
Given initial conditions and a time, figure out the end velocity. 
param_t loadParameterWithDeprecation(const ros::NodeHandle &nh, const std::string current_name, const std::string old_name, const param_t &default_value)
void initialize(ros::NodeHandle &nh) override
double time_granularity_
If discretizing by time, the amount of time between each point in the traj.