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 13 #include <sensor_msgs/PointCloud.h> 14 #include <nav2d_operator/cmd.h> 74 double evaluateAction(
double direction,
double velocity,
bool debug =
false);
95 inline sensor_msgs::PointCloud*
getPointCloud(
double direction,
double velocity);
ros::Publisher mPlanPublisher
void executeCommand()
Generates and sends Twist-Message to Robot This is the Operator'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 evaluateAction(double direction, double velocity, bool debug=false)
Calculate the action value of a given command.
costmap_2d::Costmap2D * mCostmap
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.
costmap_2d::Costmap2DROS * mLocalMap
ros::Publisher mControlPublisher
std::string mOdometryFrame
double findBestDirection()
Evaluates all possible directions with a fixed resolution.
tf::TransformListener mTfListener
unsigned int mRecoverySteps
sensor_msgs::PointCloud * mTrajTable[(LUT_RESOLUTION *4)+2]