teleop_twist.h
Go to the documentation of this file.
00001 #ifndef _TELEOP_TWIST_H_
00002 #define _TELEOP_TWIST_H_
00003 
00004 #include <ardrone_autonomy/ardrone_sdk.h>
00005 #include <geometry_msgs/Twist.h>
00006 #include <std_msgs/Empty.h>
00007 #include <std_srvs/Empty.h>
00008 #include <ardrone_autonomy/CamSelect.h>
00009 #include <ardrone_autonomy/LedAnim.h>
00010 #include <ardrone_autonomy/FlightAnim.h>
00011 #include <ardrone_autonomy/RecordEnable.h>
00012 
00013 #define _EPS 1.0e-6 
00014 
00015 extern input_device_t teleop;
00016 
00017 void cmdVelCallback(const geometry_msgs::TwistConstPtr &msg);
00018 void landCallback(const std_msgs::Empty &msg);
00019 void resetCallback(const std_msgs::Empty &msg);
00020 void takeoffCallback(const std_msgs::Empty &msg);
00021 
00022 //void toggleCamCallback(const std_msgs::Empty &msg);
00023 bool setCamChannelCallback(ardrone_autonomy::CamSelect::Request& request, ardrone_autonomy::CamSelect::Response& response);
00024 bool toggleCamCallback(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);
00025 bool setLedAnimationCallback(ardrone_autonomy::LedAnim::Request& request, ardrone_autonomy::LedAnim::Response& response);
00026 bool flatTrimCallback(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);
00027 bool setFlightAnimationCallback(ardrone_autonomy::FlightAnim::Request& request, ardrone_autonomy::FlightAnim::Response& response);
00028 bool setRecordCallback(ardrone_autonomy::RecordEnable::Request &request, ardrone_autonomy::RecordEnable::Response& response);
00029 
00030 //All global drone configs that should be sent on init
00031 
00032 #define DEFAULT_CAM_STATE 0
00033 #define DEFAULT_NAVDATA_DEMO 0
00034 
00035 extern int cam_state;
00036 extern int set_navdata_demo_value;
00037 extern int32_t detect_enemy_color;
00038 extern int32_t detect_groundstripes_color;
00039 extern int32_t detect_indoor_hull; //1: Indoor Hull
00040 extern int32_t detect_dtype;
00041 extern int32_t detect_hori_type;
00042 extern int32_t detect_vert_type;
00043 extern int32_t detect_disable_placeholder;
00044 extern int32_t detect_enable_placeholder;
00045 
00046 
00047 #endif
00048 


ardrone_autonomy
Author(s): Mani Monajjemi, Mani Monajjemi
autogenerated on Sun Oct 5 2014 22:17:06