#include <RobotOperator.h>
| Public Member Functions | |
| void | executeCommand () | 
| Generates and sends Twist-Message to Robot This is the Operator's core function and should be called periodically. | |
| void | receiveCommand (const nav2d_operator::cmd::ConstPtr &msg) | 
| Callback function to receive move commands. | |
| RobotOperator () | |
| ~RobotOperator () | |
| Private Member Functions | |
| int | calculateFreeSpace (sensor_msgs::PointCloud *cloud) | 
| Calculates the distance the robot can move following the given trajectory. | |
| double | evaluateAction (double direction, double velocity, bool debug=false) | 
| Calculate the action value of a given command. | |
| double | findBestDirection () | 
| Evaluates all possible directions with a fixed resolution. | |
| sensor_msgs::PointCloud * | getPointCloud (double direction, double velocity) | 
| Get the trajectory defined by the given movement command. | |
| void | initTrajTable () | 
| Initializes look-up tables This calculates the trajectories of all possible direction commands. Must be called once before the Operator is used. | |
| Private Attributes | |
| ros::Subscriber | mCommandSubscriber | 
| int | mConformanceWeight | 
| int | mContinueWeight | 
| ros::Publisher | mControlPublisher | 
| costmap_2d::Costmap2D * | mCostmap | 
| ros::Publisher | mCostPublisher | 
| double | mCurrentDirection | 
| double | mCurrentVelocity | 
| double | mDesiredDirection | 
| double | mDesiredVelocity | 
| int | mDistanceWeight | 
| int | mDriveMode | 
| costmap_2d::Costmap2DROS * | mLocalMap | 
| double | mMaxFreeSpace | 
| double | mMaxVelocity | 
| std::string | mOdometryFrame | 
| ros::Publisher | mPlanPublisher | 
| bool | mPublishRoute | 
| double | mRasterSize | 
| unsigned int | mRecoverySteps | 
| std::string | mRobotFrame | 
| double | mSafetyDecay | 
| int | mSafetyWeight | 
| tf::TransformListener | mTfListener | 
| ros::Publisher | mTrajectoryPublisher | 
| sensor_msgs::PointCloud * | mTrajTable [(LUT_RESOLUTION *4)+2] | 
Definition at line 30 of file RobotOperator.h.
Definition at line 8 of file RobotOperator.cpp.
Definition at line 57 of file RobotOperator.cpp.
| int RobotOperator::calculateFreeSpace | ( | sensor_msgs::PointCloud * | cloud | ) |  [private] | 
Calculates the distance the robot can move following the given trajectory.
| cloud | PointCloud defining a trajectory | 
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.
| direction | How to move the robot | 
| velocity | Only used to distinguish forward and backward motion | 
| debug | Publish result of evaluation functions on debug topic | 
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.
Definition at line 494 of file RobotOperator.cpp.
| sensor_msgs::PointCloud * RobotOperator::getPointCloud | ( | double | direction, | 
| double | velocity | ||
| ) |  [inline, private] | 
Get the trajectory defined by the given movement command.
| direction | How to move the robot | 
| velocity | Only used to distinguish forward and backward motion | 
Definition at line 514 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.
| 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.
Definition at line 104 of file RobotOperator.h.
| int RobotOperator::mConformanceWeight  [private] | 
Definition at line 125 of file RobotOperator.h.
| int RobotOperator::mContinueWeight  [private] | 
Definition at line 126 of file RobotOperator.h.
Definition at line 105 of file RobotOperator.h.
| costmap_2d::Costmap2D* RobotOperator::mCostmap  [private] | 
Definition at line 99 of file RobotOperator.h.
| ros::Publisher RobotOperator::mCostPublisher  [private] | 
Definition at line 108 of file RobotOperator.h.
| double RobotOperator::mCurrentDirection  [private] | 
Definition at line 113 of file RobotOperator.h.
| double RobotOperator::mCurrentVelocity  [private] | 
Definition at line 112 of file RobotOperator.h.
| double RobotOperator::mDesiredDirection  [private] | 
Definition at line 111 of file RobotOperator.h.
| double RobotOperator::mDesiredVelocity  [private] | 
Definition at line 110 of file RobotOperator.h.
| int RobotOperator::mDistanceWeight  [private] | 
Definition at line 123 of file RobotOperator.h.
| int RobotOperator::mDriveMode  [private] | 
Definition at line 114 of file RobotOperator.h.
| costmap_2d::Costmap2DROS* RobotOperator::mLocalMap  [private] | 
Definition at line 98 of file RobotOperator.h.
| double RobotOperator::mMaxFreeSpace  [private] | 
Definition at line 121 of file RobotOperator.h.
| double RobotOperator::mMaxVelocity  [private] | 
Definition at line 118 of file RobotOperator.h.
| std::string RobotOperator::mOdometryFrame  [private] | 
Definition at line 128 of file RobotOperator.h.
| ros::Publisher RobotOperator::mPlanPublisher  [private] | 
Definition at line 107 of file RobotOperator.h.
| bool RobotOperator::mPublishRoute  [private] | 
Definition at line 120 of file RobotOperator.h.
| double RobotOperator::mRasterSize  [private] | 
Definition at line 100 of file RobotOperator.h.
| unsigned int RobotOperator::mRecoverySteps  [private] | 
Definition at line 131 of file RobotOperator.h.
| std::string RobotOperator::mRobotFrame  [private] | 
Definition at line 129 of file RobotOperator.h.
| double RobotOperator::mSafetyDecay  [private] | 
Definition at line 122 of file RobotOperator.h.
| int RobotOperator::mSafetyWeight  [private] | 
Definition at line 124 of file RobotOperator.h.
Definition at line 102 of file RobotOperator.h.
Definition at line 106 of file RobotOperator.h.
| sensor_msgs::PointCloud* RobotOperator::mTrajTable[(LUT_RESOLUTION *4)+2]  [private] | 
Definition at line 116 of file RobotOperator.h.