#include <twirling_cost_function.h>
Public Member Functions | |
bool | prepare () |
double | scoreTrajectory (Trajectory &traj) |
TwirlingCostFunction () | |
~TwirlingCostFunction () | |
Public Member Functions inherited from base_local_planner::TrajectoryCostFunction | |
double | getScale () |
void | setScale (double scale) |
virtual | ~TrajectoryCostFunction () |
Additional Inherited Members | |
Protected Member Functions inherited from base_local_planner::TrajectoryCostFunction | |
TrajectoryCostFunction (double scale=1.0) | |
This class provides a cost based on how much a robot "twirls" on its way to the goal. With differential-drive robots, there isn't a choice, but with holonomic or near-holonomic robots, sometimes a robot spins more than you'd like on its way to a goal. This class provides a way to assign a penalty purely to rotational velocities.
Definition at line 52 of file twirling_cost_function.h.
|
inline |
Definition at line 55 of file twirling_cost_function.h.
|
inline |
Definition at line 56 of file twirling_cost_function.h.
|
inlinevirtual |
General updating of context values if required. Subclasses may overwrite. Return false in case there is any error.
Implements base_local_planner::TrajectoryCostFunction.
Definition at line 60 of file twirling_cost_function.h.
|
virtual |
return a score for trajectory traj
Implements base_local_planner::TrajectoryCostFunction.
Definition at line 14 of file twirling_cost_function.cpp.