54 if (controller_frequency > 0)
60 ROS_WARN_NAMED(
"LimitedAccelGenerator",
"A controller_frequency less than or equal to 0 has been set. " 61 "Ignoring the parameter, assuming a rate of 20Hz");
70 nh.
param(
"use_dwa", use_dwa,
true);
74 "Please use StandardTrajectoryGenerator for that functionality.");
85 const nav_2d_msgs::Twist2D& start_vel,
const double dt)
void startNewIteration(const nav_2d_msgs::Twist2D ¤t_velocity) override
#define ROS_WARN_NAMED(name,...)
param_t searchAndGetParam(const ros::NodeHandle &nh, const std::string ¶m_name, const param_t &default_value)
Limits the acceleration in the generated trajectories to a fraction of the simulated time...
void initialize(ros::NodeHandle &nh) override
double acceleration_time_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void checkUseDwaParam(const ros::NodeHandle &nh) override
Check if the deprecated use_dwa parameter is set to the functionality that matches this class...
std::shared_ptr< VelocityIterator > velocity_iterator_
bool getParam(const std::string &key, std::string &s) const
bool hasParam(const std::string &key) const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
nav_2d_msgs::Twist2D computeNewVelocity(const nav_2d_msgs::Twist2D &cmd_vel, const nav_2d_msgs::Twist2D &start_vel, const double dt) override
Calculate the velocity after a set period of time, given the desired velocity and acceleration limits...
void initialize(ros::NodeHandle &nh) override