#include <ros/ros.h>
#include <angles/angles.h>
#include <driver_base/SensorLevels.h>
#include <dynamic_reconfigure/server.h>
#include "device_impl.h"
#include <art_msgs/ArtVehicle.h>
#include <art_msgs/ArtHertz.h>
#include <art_msgs/CarDriveStamped.h>
#include <art_msgs/CarCommand.h>
#include <art_msgs/Epsilon.h>
#include <art_msgs/Gear.h>
#include <art_msgs/LearningCommand.h>
#include <art_msgs/PilotState.h>
#include <art/conversions.h>
#include <art/steering.h>
#include <art_pilot/PilotConfig.h>
#include "accel.h"
Go to the source code of this file.
Classes | |
class | PilotNode |
controls the ART vehicle brake, throttle, steering and transmission More... | |
Typedefs | |
typedef art_pilot::PilotConfig | Config |
typedef art_msgs::DriverState | DriverState |
Functions | |
int | main (int argc, char **argv) |
ROS node for controlling direction and speed of the ART autonomous vehicle.
(optionally) stop if no commands received recently.
shift to Park, when appropriate
distinguish device failures before and after initialization
deprecate old CarCommand message interface
Definition in file pilot.cc.
typedef art_msgs::DriverState DriverState |