#include <RobotOperator.h>
- Author
- Sebastian Kasperski
- Date
- 03/25/14
Definition at line 30 of file RobotOperator.h.
RobotOperator::RobotOperator |
( |
| ) |
|
RobotOperator::~RobotOperator |
( |
| ) |
|
Calculates the distance the robot can move following the given trajectory.
- Parameters
-
cloud | PointCloud defining a trajectory |
- Returns
- Nmber of free cells
Definition at line 364 of file RobotOperator.cpp.
double RobotOperator::evaluateAction |
( |
double |
direction, |
|
|
double |
velocity, |
|
|
bool |
debug = false |
|
) |
| |
|
private |
Calculate the action value of a given command.
- Parameters
-
direction | How to move the robot |
velocity | Only used to distinguish forward and backward motion |
debug | Publish result of evaluation functions on debug topic |
- Returns
- Weighted sum of all evaluation functions The given action is rated by 4 different evaluation functions: Free Space: How far can the robot move following this command Safety: How close will it get near obstacles Conformance: How good does it follow the commanded direction Continuity: (experimental!) How does it conform with the last issued command
Definition at line 388 of file RobotOperator.cpp.
void RobotOperator::executeCommand |
( |
| ) |
|
Generates and sends Twist-Message to Robot This is the Operator's core function and should be called periodically.
Definition at line 200 of file RobotOperator.cpp.
double RobotOperator::findBestDirection |
( |
| ) |
|
|
private |
Evaluates all possible directions with a fixed resolution.
- Returns
- Best evaluated direction
Definition at line 489 of file RobotOperator.cpp.
Get the trajectory defined by the given movement command.
- Parameters
-
direction | How to move the robot |
velocity | Only used to distinguish forward and backward motion |
- Returns
- A pointer to the PointCloud defined in the robot coordinate frame
Definition at line 509 of file RobotOperator.cpp.
void RobotOperator::initTrajTable |
( |
| ) |
|
|
private |
Initializes look-up tables This calculates the trajectories of all possible direction commands. Must be called once before the Operator is used.
Definition at line 65 of file RobotOperator.cpp.
void RobotOperator::receiveCommand |
( |
const nav2d_operator::cmd::ConstPtr & |
msg | ) |
|
Callback function to receive move commands.
- Parameters
-
msg | Command-Message Direction [-1.0 .. 1.0]: -1(rotate left); 0(straight); 1(rotate right) Velocity [-1.0 .. 1.0]: -1(full speed back); 0(stop); 1(full speed ahead) Mode: 0(Avoid obstacles); 1(Stop at obstacles) |
Definition at line 182 of file RobotOperator.cpp.
int RobotOperator::mConformanceWeight |
|
private |
int RobotOperator::mContinueWeight |
|
private |
double RobotOperator::mCurrentDirection |
|
private |
double RobotOperator::mCurrentVelocity |
|
private |
double RobotOperator::mDesiredDirection |
|
private |
double RobotOperator::mDesiredVelocity |
|
private |
int RobotOperator::mDriveMode |
|
private |
int RobotOperator::mEscapeWeight |
|
private |
double RobotOperator::mMaxFreeSpace |
|
private |
double RobotOperator::mMaxVelocity |
|
private |
std::string RobotOperator::mOdometryFrame |
|
private |
bool RobotOperator::mPublishRoute |
|
private |
double RobotOperator::mRasterSize |
|
private |
unsigned int RobotOperator::mRecoverySteps |
|
private |
std::string RobotOperator::mRobotFrame |
|
private |
double RobotOperator::mSafetyDecay |
|
private |
int RobotOperator::mSafetyWeight |
|
private |
The documentation for this class was generated from the following files: