#include <ros/ros.h>
#include <nodelet/nodelet.h>
#include <pluginlib/class_list_macros.h>
#include <diagnostic_updater/diagnostic_updater.h>
#include "starmac_msgs/OperatorCommands.h"
#include "flyer_controller/control_mode_status.h"
#include "flyer_controller/control_mode_output.h"
#include "flyer_controller/control_mode_cmd.h"
#include "flyer_controller/control_utils.h"
#include <nav_msgs/Odometry.h>
#include <angles/angles.h>
#include <tf/tf.h>
#include <algorithm>
Go to the source code of this file.
Classes | |
class | flyer_controller::ControlMode |
Namespaces | |
namespace | flyer_controller |
namespace | flyer_controller::ControlModeTypes |
Defines | |
#define | CHECK_PARAMETER(x, msg) {if(!(x)) {ROS_FATAL_STREAM(msg); ros::requestShutdown(); return;}} |
Typedefs | |
typedef ControlModeStates | flyer_controller::ControlModeTypes::ControlModeState |
Enumerations | |
enum | flyer_controller::ControlModeTypes::ControlModeStates { flyer_controller::ControlModeTypes::ERROR = 0, flyer_controller::ControlModeTypes::OFF = 1, flyer_controller::ControlModeTypes::IDLE = 2, flyer_controller::ControlModeTypes::STANDBY = 3, flyer_controller::ControlModeTypes::ACTIVE = 4 } |
#define CHECK_PARAMETER | ( | x, | |
msg | |||
) | {if(!(x)) {ROS_FATAL_STREAM(msg); ros::requestShutdown(); return;}} |
Definition at line 53 of file control_mode.h.