#include <xy_theta_iterator.h>

Public Member Functions | |
| bool | hasMoreTwists () override |
| void | initialize (ros::NodeHandle &nh, KinematicParameters::Ptr kinematics) override |
| nav_2d_msgs::Twist2D | nextTwist () override |
| void | startNewIteration (const nav_2d_msgs::Twist2D ¤t_velocity, double dt) override |
| XYThetaIterator () | |
Public Member Functions inherited from dwb_plugins::VelocityIterator | |
| virtual | ~VelocityIterator () |
Protected Member Functions | |
| virtual bool | isValidVelocity () |
| void | iterateToValidVelocity () |
Protected Attributes | |
| KinematicParameters::Ptr | kinematics_ |
| std::shared_ptr< OneDVelocityIterator > | th_it_ |
| int | vtheta_samples_ |
| int | vx_samples_ |
| int | vy_samples_ |
| std::shared_ptr< OneDVelocityIterator > | x_it_ |
| std::shared_ptr< OneDVelocityIterator > | y_it_ |
Definition at line 44 of file xy_theta_iterator.h.
|
inline |
Definition at line 47 of file xy_theta_iterator.h.
|
overridevirtual |
Implements dwb_plugins::VelocityIterator.
Definition at line 70 of file xy_theta_iterator.cpp.
|
overridevirtual |
Implements dwb_plugins::VelocityIterator.
Definition at line 41 of file xy_theta_iterator.cpp.
|
protectedvirtual |
Definition at line 65 of file xy_theta_iterator.cpp.
|
protected |
Definition at line 88 of file xy_theta_iterator.cpp.
|
overridevirtual |
Implements dwb_plugins::VelocityIterator.
Definition at line 76 of file xy_theta_iterator.cpp.
|
overridevirtual |
Implements dwb_plugins::VelocityIterator.
Definition at line 49 of file xy_theta_iterator.cpp.
|
protected |
Definition at line 56 of file xy_theta_iterator.h.
|
protected |
Definition at line 58 of file xy_theta_iterator.h.
|
protected |
Definition at line 55 of file xy_theta_iterator.h.
|
protected |
Definition at line 55 of file xy_theta_iterator.h.
|
protected |
Definition at line 55 of file xy_theta_iterator.h.
|
protected |
Definition at line 58 of file xy_theta_iterator.h.
|
protected |
Definition at line 58 of file xy_theta_iterator.h.