A dynamically reconfigurable class containing one representation of the robot's kinematics.
More...
#include <kinematic_parameters.h>
|
void | reconfigureCB (KinematicParamsConfig &config, uint32_t level) |
|
A dynamically reconfigurable class containing one representation of the robot's kinematics.
Definition at line 50 of file kinematic_parameters.h.
◆ Ptr
◆ KinematicParameters()
dwb_plugins::KinematicParameters::KinematicParameters |
( |
| ) |
|
◆ getAccTheta()
double dwb_plugins::KinematicParameters::getAccTheta |
( |
| ) |
|
|
inline |
◆ getAccX()
double dwb_plugins::KinematicParameters::getAccX |
( |
| ) |
|
|
inline |
◆ getAccY()
double dwb_plugins::KinematicParameters::getAccY |
( |
| ) |
|
|
inline |
◆ getDecelTheta()
double dwb_plugins::KinematicParameters::getDecelTheta |
( |
| ) |
|
|
inline |
◆ getDecelX()
double dwb_plugins::KinematicParameters::getDecelX |
( |
| ) |
|
|
inline |
◆ getDecelY()
double dwb_plugins::KinematicParameters::getDecelY |
( |
| ) |
|
|
inline |
◆ getMaxTheta()
double dwb_plugins::KinematicParameters::getMaxTheta |
( |
| ) |
|
|
inline |
◆ getMaxX()
double dwb_plugins::KinematicParameters::getMaxX |
( |
| ) |
|
|
inline |
◆ getMaxY()
double dwb_plugins::KinematicParameters::getMaxY |
( |
| ) |
|
|
inline |
◆ getMinSpeedTheta()
double dwb_plugins::KinematicParameters::getMinSpeedTheta |
( |
| ) |
|
|
inline |
◆ getMinSpeedXY()
double dwb_plugins::KinematicParameters::getMinSpeedXY |
( |
| ) |
|
|
inline |
◆ getMinTheta()
double dwb_plugins::KinematicParameters::getMinTheta |
( |
| ) |
|
|
inline |
◆ getMinX()
double dwb_plugins::KinematicParameters::getMinX |
( |
| ) |
|
|
inline |
◆ getMinY()
double dwb_plugins::KinematicParameters::getMinY |
( |
| ) |
|
|
inline |
◆ initialize()
void dwb_plugins::KinematicParameters::initialize |
( |
const ros::NodeHandle & |
nh | ) |
|
◆ isValidSpeed()
bool dwb_plugins::KinematicParameters::isValidSpeed |
( |
double |
x, |
|
|
double |
y, |
|
|
double |
theta |
|
) |
| |
Check to see whether the combined x/y/theta velocities are valid.
- Returns
- True if the magnitude hypot(x,y) and theta are within the robot's absolute limits
This is based on three parameters: min_speed_xy, max_speed_xy and min_speed_theta. The speed is valid if 1) The combined magnitude hypot(x,y) is less than max_speed_xy (or max_speed_xy is negative) AND 2) min_speed_xy is negative or min_speed_theta is negative or hypot(x,y) is greater than min_speed_xy or fabs(theta) is greater than min_speed_theta.
In English, it makes sure the diagonal motion is not too fast, and that the velocity is moving in some meaningful direction.
In Latin, quod si motus sit signum quaerit et movere ieiunium et significantissime comprehendite.
Definition at line 116 of file kinematic_parameters.cpp.
◆ reconfigureCB()
void dwb_plugins::KinematicParameters::reconfigureCB |
( |
KinematicParamsConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protected |
◆ acc_lim_theta_
double dwb_plugins::KinematicParameters::acc_lim_theta_ |
|
protected |
◆ acc_lim_x_
double dwb_plugins::KinematicParameters::acc_lim_x_ |
|
protected |
◆ acc_lim_y_
double dwb_plugins::KinematicParameters::acc_lim_y_ |
|
protected |
◆ decel_lim_theta_
double dwb_plugins::KinematicParameters::decel_lim_theta_ |
|
protected |
◆ decel_lim_x_
double dwb_plugins::KinematicParameters::decel_lim_x_ |
|
protected |
◆ decel_lim_y_
double dwb_plugins::KinematicParameters::decel_lim_y_ |
|
protected |
◆ dsrv_
std::shared_ptr<dynamic_reconfigure::Server<KinematicParamsConfig> > dwb_plugins::KinematicParameters::dsrv_ |
|
protected |
◆ max_speed_xy_
double dwb_plugins::KinematicParameters::max_speed_xy_ |
|
protected |
◆ max_speed_xy_sq_
double dwb_plugins::KinematicParameters::max_speed_xy_sq_ |
|
protected |
◆ max_vel_theta_
double dwb_plugins::KinematicParameters::max_vel_theta_ |
|
protected |
◆ max_vel_x_
double dwb_plugins::KinematicParameters::max_vel_x_ |
|
protected |
◆ max_vel_y_
double dwb_plugins::KinematicParameters::max_vel_y_ |
|
protected |
◆ min_speed_theta_
double dwb_plugins::KinematicParameters::min_speed_theta_ |
|
protected |
◆ min_speed_xy_
double dwb_plugins::KinematicParameters::min_speed_xy_ |
|
protected |
◆ min_speed_xy_sq_
double dwb_plugins::KinematicParameters::min_speed_xy_sq_ |
|
protected |
◆ min_vel_x_
double dwb_plugins::KinematicParameters::min_vel_x_ |
|
protected |
◆ min_vel_y_
double dwb_plugins::KinematicParameters::min_vel_y_ |
|
protected |
The documentation for this class was generated from the following files: