#include <actionlib/server/simple_action_server.h>#include <costmap_2d/costmap_2d.h>#include <geometry_msgs/Twist.h>#include <navfn/navfn.h>#include <nav_msgs/OccupancyGrid.h>#include <ros/ros.h>#include <sensor_msgs/Image.h>#include <sys/time.h>#include <youbot_overhead_localization/CostmapCost.h>#include <youbot_overhead_localization/GetCost.h>#include <youbot_overhead_localization/Path.h>#include <youbot_overhead_localization/PlanPathAction.h>#include <youbot_overhead_localization/PlanPathGoal.h>#include <youbot_overhead_localization/Pose2d.h>#include <youbot_overhead_vision/CalibCameraImg.h>#include <youbot_overhead_vision/CoordConversion.h>

Go to the source code of this file.
Classes | |
| class | pathPlanner |
| actionlib server that plans and executes paths for the robot base More... | |
Defines | |
| #define | A -0.8 |
| #define | B1 0.1 |
| #define | B2 0.1 |
| #define | KD_ANG .01 |
| #define | KD_LIN .008 |
| #define | KI_ANG .0001 |
| #define | KI_LIN .002 |
| #define | KP_ANG 4 |
| #define | KP_LIN 2.3 |
| #define | MAX_SPEED .5; |
| #define | PATH_TIMEOUT 120.0 |
| #define | PI 3.14159 |
| #define | REAL_TOP_CAMERA_OFFSET 476 |
| #define | SIG_THRESH -.995 |
| #define | SIM_TOP_CAMERA_OFFSET 539 |
| #define A -0.8 |
Definition at line 29 of file pathPlanner.h.
| #define B1 0.1 |
This file contains the pathPlanner class definition, which plans and follows paths for the robot base.
Definition at line 27 of file pathPlanner.h.
| #define B2 0.1 |
Definition at line 28 of file pathPlanner.h.
| #define KD_ANG .01 |
Definition at line 35 of file pathPlanner.h.
| #define KD_LIN .008 |
Definition at line 38 of file pathPlanner.h.
| #define KI_ANG .0001 |
Definition at line 34 of file pathPlanner.h.
| #define KI_LIN .002 |
Definition at line 37 of file pathPlanner.h.
| #define KP_ANG 4 |
Definition at line 33 of file pathPlanner.h.
| #define KP_LIN 2.3 |
Definition at line 36 of file pathPlanner.h.
| #define MAX_SPEED .5; |
Definition at line 45 of file pathPlanner.h.
| #define PATH_TIMEOUT 120.0 |
Definition at line 43 of file pathPlanner.h.
| #define PI 3.14159 |
Definition at line 47 of file pathPlanner.h.
| #define REAL_TOP_CAMERA_OFFSET 476 |
Definition at line 41 of file pathPlanner.h.
| #define SIG_THRESH -.995 |
Definition at line 30 of file pathPlanner.h.
| #define SIM_TOP_CAMERA_OFFSET 539 |
Definition at line 40 of file pathPlanner.h.