#include <string.h>
#include <vector>
#include <queue>
#include <stdint.h>
#include <ros/ros.h>
#include <math.h>
#include <cstdlib>
#include <purepursuit_planner/Component.h>
#include <ackermann_msgs/AckermannDriveStamped.h>
#include <nav_msgs/Odometry.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
#include "diagnostic_msgs/DiagnosticStatus.h"
#include "diagnostic_updater/diagnostic_updater.h"
#include "diagnostic_updater/update_functions.h"
#include "diagnostic_updater/DiagnosticStatusWrapper.h"
#include "diagnostic_updater/publisher.h"
#include <actionlib/server/simple_action_server.h>
#include <planner_msgs/GoToAction.h>
#include <planner_msgs/goal.h>
#include <geometry_msgs/Pose2D.h>
Go to the source code of this file.
Classes | |
struct | MagnetStruct |
Data structure for a Magnet. More... | |
class | Path |
class to manage the waypoints and magnets of the current path More... | |
class | purepursuit_planner_node |
struct | Waypoint |
Data structure for a Waypoint. More... | |
Defines | |
#define | AGVS_DEFAULT_KR 0.20 |
#define | AGVS_FIRST_DECELERATION_DISTANCE 0.5 |
#define | AGVS_FIRST_DECELERATION_MAXSPEED 0.15 |
#define | AGVS_SECOND_DECELERATION_DISTANCE 0.25 |
#define | AGVS_SECOND_DECELERATION_MAXSPEED 0.1 |
#define | AGVS_TURN_RADIUS 0.20 |
#define | BEZIER_CONTROL_POINTS 5 |
#define | D_LOOKAHEAD_MAX 1.1 |
#define | D_LOOKAHEAD_MIN 0.3 |
#define | D_WHEEL_ROBOT_CENTER 0.478 |
#define | MAP_TIMEOUT_ERROR 0.2 |
#define | MAX_SPEED 1.2 |
#define | MAX_SPEED_LVL1 0.5 |
#define | MAX_SPEED_LVL2 0.3 |
#define | MIN_ANGLE_BEZIER 0.261799388 |
#define | ODOM_TIMEOUT_ERROR 0.2 |
#define | WAYPOINT_POP_DISTANCE_M 0.10 |
Typedefs | |
typedef struct MagnetStruct | MagnetStruct |
Data structure for a Magnet. | |
typedef struct Waypoint | Waypoint |
Data structure for a Waypoint. | |
Enumerations | |
enum | { ODOM_SOURCE = 1, MAP_SOURCE = 2 } |
Functions | |
int | main (int argc, char **argv) |
#define AGVS_DEFAULT_KR 0.20 |
Definition at line 55 of file purepursuit_planner.cpp.
#define AGVS_FIRST_DECELERATION_DISTANCE 0.5 |
Definition at line 51 of file purepursuit_planner.cpp.
#define AGVS_FIRST_DECELERATION_MAXSPEED 0.15 |
Definition at line 52 of file purepursuit_planner.cpp.
#define AGVS_SECOND_DECELERATION_DISTANCE 0.25 |
Definition at line 53 of file purepursuit_planner.cpp.
#define AGVS_SECOND_DECELERATION_MAXSPEED 0.1 |
Definition at line 54 of file purepursuit_planner.cpp.
#define AGVS_TURN_RADIUS 0.20 |
Definition at line 37 of file purepursuit_planner.cpp.
#define BEZIER_CONTROL_POINTS 5 |
Definition at line 39 of file purepursuit_planner.cpp.
#define D_LOOKAHEAD_MAX 1.1 |
Definition at line 42 of file purepursuit_planner.cpp.
#define D_LOOKAHEAD_MIN 0.3 |
Definition at line 41 of file purepursuit_planner.cpp.
#define D_WHEEL_ROBOT_CENTER 0.478 |
Definition at line 43 of file purepursuit_planner.cpp.
#define MAP_TIMEOUT_ERROR 0.2 |
Definition at line 36 of file purepursuit_planner.cpp.
#define MAX_SPEED 1.2 |
Definition at line 47 of file purepursuit_planner.cpp.
#define MAX_SPEED_LVL1 0.5 |
Definition at line 45 of file purepursuit_planner.cpp.
#define MAX_SPEED_LVL2 0.3 |
Definition at line 46 of file purepursuit_planner.cpp.
#define MIN_ANGLE_BEZIER 0.261799388 |
Definition at line 38 of file purepursuit_planner.cpp.
#define ODOM_TIMEOUT_ERROR 0.2 |
Definition at line 35 of file purepursuit_planner.cpp.
#define WAYPOINT_POP_DISTANCE_M 0.10 |
Definition at line 49 of file purepursuit_planner.cpp.
typedef struct MagnetStruct MagnetStruct |
Data structure for a Magnet.
anonymous enum |
Definition at line 57 of file purepursuit_planner.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 1784 of file purepursuit_planner.cpp.