Go to the documentation of this file.
55 th_it_ = std::make_shared<OneDVelocityIterator>(current_velocity.theta,
78 nav_2d_msgs::Twist2D velocity;
79 velocity.x =
x_it_->getVelocity();
80 velocity.y =
y_it_->getVelocity();
81 velocity.theta =
th_it_->getVelocity();
98 if (
y_it_->isFinished())
virtual bool isValidVelocity()
std::shared_ptr< OneDVelocityIterator > th_it_
void startNewIteration(const nav_2d_msgs::Twist2D ¤t_velocity, double dt) override
void iterateToValidVelocity()
nav_2d_msgs::Twist2D nextTwist() override
param_t loadParameterWithDeprecation(const ros::NodeHandle &nh, const std::string current_name, const std::string old_name, const param_t &default_value)
bool hasMoreTwists() override
T param(const std::string ¶m_name, const T &default_val) const
std::shared_ptr< OneDVelocityIterator > y_it_
void initialize(ros::NodeHandle &nh, KinematicParameters::Ptr kinematics) override
KinematicParameters::Ptr kinematics_
std::shared_ptr< KinematicParameters > Ptr
std::shared_ptr< OneDVelocityIterator > x_it_
dwb_plugins
Author(s):
autogenerated on Sun May 18 2025 02:47:27