RobotOperator.h
Go to the documentation of this file.
00001 #ifndef OPERATOR_H
00002 #define OPERATOR_H
00003 
00004 #define NODE_NAME     "operator"
00005 #define COMMAND_TOPIC "cmd"
00006 #define CONTROL_TOPIC "cmd_vel"
00007 #define ROUTE_TOPIC   "route"
00008 #define PLAN_TOPIC    "desired"
00009 #define LUT_RESOLUTION 100
00010 
00011 #include <ros/ros.h>
00012 #include <costmap_2d/costmap_2d_ros.h>
00013 #include <sensor_msgs/PointCloud.h>
00014 #include <nav2d_operator/cmd.h>
00015 
00016 #include <string>
00017 
00030 class RobotOperator
00031 {
00032 public:
00033         // Default Constructor & Destructor
00034         RobotOperator();
00035         ~RobotOperator();
00036         
00037         // Public Methods
00045         void receiveCommand(const nav2d_operator::cmd::ConstPtr& msg);
00046 
00051         void executeCommand();
00052 
00053 private:
00054         // Internal Methods
00060         int calculateFreeSpace(sensor_msgs::PointCloud* cloud);
00061 
00074         double evaluateAction(double direction, double velocity, bool debug = false);
00075 
00080         double findBestDirection();
00081 
00087         void initTrajTable();
00088         
00095         inline sensor_msgs::PointCloud* getPointCloud(double direction, double velocity);
00096 
00097         // Internal Storage
00098         costmap_2d::Costmap2DROS* mLocalMap;
00099         costmap_2d::Costmap2D* mCostmap;
00100         double mRasterSize;
00101         
00102         tf::TransformListener mTfListener;
00103         
00104         ros::Subscriber mCommandSubscriber;
00105         ros::Publisher mControlPublisher;
00106         ros::Publisher mTrajectoryPublisher;
00107         ros::Publisher mPlanPublisher;
00108         ros::Publisher mCostPublisher;
00109         
00110         double mDesiredVelocity;
00111         double mDesiredDirection;
00112         double mCurrentVelocity;
00113         double mCurrentDirection;
00114         int mDriveMode;
00115         
00116         sensor_msgs::PointCloud* mTrajTable[(LUT_RESOLUTION * 4) + 2];
00117         
00118         double mMaxVelocity;
00119         
00120         bool mPublishRoute;
00121         double mMaxFreeSpace;
00122         double mSafetyDecay;
00123         int mDistanceWeight;
00124         int mSafetyWeight;
00125         int mConformanceWeight;
00126         int mContinueWeight;
00127 
00128         std::string mOdometryFrame;
00129         std::string mRobotFrame;
00130         
00131         unsigned int mRecoverySteps;
00132 };
00133 
00134 #endif


nav2d_operator
Author(s): Sebastian Kasperski
autogenerated on Mon Oct 6 2014 02:44:03