teleop_twist.h
Go to the documentation of this file.
00001 
00025 #ifndef ARDRONE_AUTONOMY_TELEOP_TWIST_H
00026 #define ARDRONE_AUTONOMY_TELEOP_TWIST_H
00027 
00028 #include <ardrone_autonomy/ardrone_sdk.h>
00029 #include <geometry_msgs/Twist.h>
00030 #include <std_msgs/Empty.h>
00031 #include <std_srvs/Empty.h>
00032 #include <ardrone_autonomy/CamSelect.h>
00033 #include <ardrone_autonomy/LedAnim.h>
00034 #include <ardrone_autonomy/FlightAnim.h>
00035 #include <ardrone_autonomy/RecordEnable.h>
00036 
00037 #define _EPS 1.0e-6
00038 
00039 extern input_device_t teleop;
00040 
00041 void CmdVelCallback(const geometry_msgs::TwistConstPtr &msg);
00042 void LandCallback(const std_msgs::Empty &msg);
00043 void ResetCallback(const std_msgs::Empty &msg);
00044 void TakeoffCallback(const std_msgs::Empty &msg);
00045 
00046 // void toggleCamCallback(const std_msgs::Empty &msg);
00047 bool SetCamChannelCallback(
00048     ardrone_autonomy::CamSelect::Request& request,
00049     ardrone_autonomy::CamSelect::Response& response);
00050 
00051 bool ToggleCamCallback(
00052     std_srvs::Empty::Request& request,
00053     std_srvs::Empty::Response& response);
00054 
00055 bool SetLedAnimationCallback(
00056     ardrone_autonomy::LedAnim::Request& request,
00057     ardrone_autonomy::LedAnim::Response& response);
00058 
00059 bool FlatTrimCallback(
00060     std_srvs::Empty::Request& request,
00061     std_srvs::Empty::Response& response);
00062 
00063 bool SetFlightAnimationCallback(
00064     ardrone_autonomy::FlightAnim::Request& request,
00065     ardrone_autonomy::FlightAnim::Response& response);
00066 
00067 bool SetRecordCallback(
00068     ardrone_autonomy::RecordEnable::Request &request,
00069     ardrone_autonomy::RecordEnable::Response& response);
00070 
00071 // All global drone configs that should be sent on init
00072 
00073 #define DEFAULT_CAM_STATE 0
00074 #define DEFAULT_NAVDATA_DEMO 0
00075 
00076 extern int cam_state;
00077 extern int set_navdata_demo_value;
00078 extern int32_t detect_enemy_color;
00079 extern int32_t detect_groundstripes_color;
00080 extern int32_t detect_indoor_hull;  // 1: Indoor Hull
00081 extern int32_t detect_dtype;
00082 extern int32_t detect_hori_type;
00083 extern int32_t detect_vert_type;
00084 extern int32_t detect_disable_placeholder;
00085 extern int32_t detect_enable_placeholder;
00086 
00087 #endif  // ARDRONE_AUTONOMY_TELEOP_TWIST_H


ardrone_autonomy
Author(s): Mani Monajjemi, Mani Monajjemi
autogenerated on Fri Aug 28 2015 10:07:51