RobotOperator.h
Go to the documentation of this file.
1 #ifndef OPERATOR_H
2 #define OPERATOR_H
3 
4 #define NODE_NAME "operator"
5 #define COMMAND_TOPIC "cmd"
6 #define CONTROL_TOPIC "cmd_vel"
7 #define ROUTE_TOPIC "route"
8 #define PLAN_TOPIC "desired"
9 #define LUT_RESOLUTION 100
10 
11 #include <ros/ros.h>
13 #include <sensor_msgs/PointCloud.h>
14 #include <nav2d_operator/cmd.h>
15 
16 #include <string>
17 
31 {
32 public:
33  // Default Constructor & Destructor
34  RobotOperator();
36 
37  // Public Methods
45  void receiveCommand(const nav2d_operator::cmd::ConstPtr& msg);
46 
51  void executeCommand();
52 
53 private:
54  // Internal Methods
60  int calculateFreeSpace(sensor_msgs::PointCloud* cloud);
61 
74  double evaluateAction(double direction, double velocity, bool debug = false);
75 
80  double findBestDirection();
81 
87  void initTrajTable();
88 
95  inline sensor_msgs::PointCloud* getPointCloud(double direction, double velocity);
96 
97  // Internal Storage
100  double mRasterSize;
101 
103 
109 
115 
116  sensor_msgs::PointCloud* mTrajTable[(LUT_RESOLUTION * 4) + 2];
117 
118  double mMaxVelocity;
119 
122  double mSafetyDecay;
127 
128  std::string mOdometryFrame;
129  std::string mRobotFrame;
130 
131  unsigned int mRecoverySteps;
132 };
133 
134 #endif
double mDesiredVelocity
ros::Publisher mPlanPublisher
void executeCommand()
Generates and sends Twist-Message to Robot This is the Operator&#39;s core function and should be called ...
ros::Publisher mCostPublisher
ros::Subscriber mCommandSubscriber
void initTrajTable()
Initializes look-up tables This calculates the trajectories of all possible direction commands...
sensor_msgs::PointCloud * getPointCloud(double direction, double velocity)
Get the trajectory defined by the given movement command.
double mMaxVelocity
double evaluateAction(double direction, double velocity, bool debug=false)
Calculate the action value of a given command.
double mDesiredDirection
costmap_2d::Costmap2D * mCostmap
Definition: RobotOperator.h:99
ros::Publisher mTrajectoryPublisher
int calculateFreeSpace(sensor_msgs::PointCloud *cloud)
Calculates the distance the robot can move following the given trajectory.
void receiveCommand(const nav2d_operator::cmd::ConstPtr &msg)
Callback function to receive move commands.
double mSafetyDecay
#define LUT_RESOLUTION
Definition: RobotOperator.h:9
costmap_2d::Costmap2DROS * mLocalMap
Definition: RobotOperator.h:98
double mCurrentVelocity
ros::Publisher mControlPublisher
double mCurrentDirection
std::string mOdometryFrame
double mMaxFreeSpace
std::string mRobotFrame
double findBestDirection()
Evaluates all possible directions with a fixed resolution.
tf::TransformListener mTfListener
double mRasterSize
unsigned int mRecoverySteps
sensor_msgs::PointCloud * mTrajTable[(LUT_RESOLUTION *4)+2]


nav2d_operator
Author(s): Sebastian Kasperski
autogenerated on Tue Nov 7 2017 06:02:46