sdk.h
Go to the documentation of this file.
00001 /*
00002 
00003 Copyright (c) 2011, Ascending Technologies GmbH
00004 All rights reserved.
00005 
00006 Redistribution and use in source and binary forms, with or without
00007 modification, are permitted provided that the following conditions are met:
00008 
00009  * Redistributions of source code must retain the above copyright notice,
00010    this list of conditions and the following disclaimer.
00011  * Redistributions in binary form must reproduce the above copyright
00012    notice, this list of conditions and the following disclaimer in the
00013    documentation and/or other materials provided with the distribution.
00014 
00015 THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND ANY
00016 EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00017 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00018 DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE FOR ANY
00019 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00020 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00021 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00022 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00023 LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
00024 OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
00025 DAMAGE.
00026 
00027  */
00028 
00029 #ifndef SDK_
00030 #define SDK_
00031 
00032 void SDK_mainloop(void);
00033 
00034 //--- general commands -----------------------------------------------------------------------------------------------------------------------------------------------
00035 struct WO_SDK_STRUCT {
00036 
00037         unsigned char ctrl_mode;
00038 
00039         unsigned char ctrl_enabled; //0x00: control commands are ignored by LL processor
00040                                                                 //0x01: control commands are accepted by LL processor
00041 
00042         unsigned char disable_motor_onoff_by_stick; // if true, "minimum thrust + full yaw" command will not start/stop motors
00043 };
00044 extern struct WO_SDK_STRUCT WO_SDK;
00045 
00046 //--- read sensor data -----------------------------------------------------------------------------------------------------------------------------------------------
00047 struct RO_ALL_DATA {
00048 
00049         //remote control data
00050                 unsigned short channel[8];
00051                 /*
00052                  * channel[0]: pitch
00053                  * channel[1]: roll
00054                  * channel[2]: thrust
00055                  * channel[3]: yaw
00056                  * channel[4]: serial interface enable/disable (>2048 enabled)
00057                  * channel[5]: manual / height control / GPS + height control (0 -> manual mode; 2048 -> height mode; 4095 -> GPS mode)
00058                  *
00059                  * range of each channel: 0..4095
00060                  */
00061 
00062         //angles derived by integration of gyro_outputs, drift compensated by data fusion; -90000..+90000 pitch(nick) and roll, 0..360000 yaw; 1000 = 1 degree
00063             int angle_pitch;
00064             int angle_roll;
00065             int angle_yaw;
00066 
00067         //angular velocities, bias free, in 0.0154 °/s (=> 64.8 = 1 °/s)
00068             int angvel_pitch;
00069             int angvel_roll;
00070             int angvel_yaw;
00071 
00072         //acc-sensor outputs, calibrated: -10000..+10000 = -1g..+1g, body frame coordinate system
00073             short acc_x;
00074             short acc_y;
00075             short acc_z;
00076 
00077         //magnetic field sensors output, offset free and scaled to +-2500 = +- earth field strength;
00078             int Hx;
00079             int Hy;
00080             int Hz;
00081 
00082         //RPM measurements (0..200)
00083         /*
00084          * Quadcopter (AscTec Hummingbird, AscTec Pelican)
00085          *
00086          * motor[0]: front
00087          * motor[1]: rear
00088          * motor[2]: left
00089          * motor[3]: right
00090          *
00091          */
00092 
00093         /*
00094          * Hexcopter (AscTec Firefly)
00095          *
00096          * motor[0]: front-left
00097          * motor[1]: left
00098          * motor[2]: rear-left
00099          * motor[3]: rear-right
00100          * motor[4]: right
00101          * motor[5]: front-right
00102          *
00103          */
00104             unsigned char motor_rpm[6];
00105 
00106         //latitude/longitude in degrees * 10^7
00107                 int GPS_latitude;
00108                 int GPS_longitude;
00109 
00110         //GPS height in mm
00111                 int GPS_height;
00112 
00113         //speed in x (E/W) and y(N/S) in mm/s
00114                 int GPS_speed_x;
00115                 int GPS_speed_y;
00116 
00117         //GPS heading in deg * 1000
00118                 int GPS_heading;
00119 
00120         //accuracy estimates in mm and mm/s
00121                 unsigned int GPS_position_accuracy;
00122                 unsigned int GPS_height_accuracy;
00123                 unsigned int GPS_speed_accuracy;
00124 
00125         //number of satellites used in NAV solution
00126                 unsigned int GPS_sat_num;
00127 
00128         // GPS status information: Bit7...Bit3: 0; Bit 2: longitude direction; Bit1: latitude direction; Bit 0: GPS lock
00129                 int GPS_status;
00130 
00131                 unsigned int GPS_time_of_week;  //[ms] (1 week = 604,800 s)
00132                 unsigned short GPS_week;                // starts from beginning of year 1980
00133 
00134         //height in mm (after data fusion)
00135                 int fusion_height;
00136 
00137         //diff. height in mm/s (after data fusion)
00138                 int fusion_dheight;
00139 
00140         //GPS data fused with all other sensors (best estimations)
00141                 int fusion_latitude;    //Fused latitude in degrees * 10^7
00142                 int fusion_longitude;   //Fused longitude in degrees * 10^7
00143 
00144                 short fusion_speed_x;   //[mm/s]
00145                 short fusion_speed_y;   //[mm/s]
00146 
00147 }; //************************************************************
00148 extern struct RO_ALL_DATA RO_ALL_Data;
00149 
00150 
00151 struct RO_RC_DATA {
00152 
00153         unsigned short channel[8];
00154         /*
00155          * channel[0]: pitch
00156          * channel[1]: roll
00157          * channel[2]: thrust
00158          * channel[3]: yaw
00159          * channel[4]: serial interface enable/disable (>2048 enabled)
00160          * channel[5]: manual / height control / GPS + height control (0-manual-1500-height-2500-GPS-4095)
00161          *
00162          * range of each channel: 0..4095
00163          */
00164 };
00165 extern struct RO_RC_DATA RO_RC_Data;
00166 
00167 
00168 
00169 //--- send commands -----------------------------------------------------------------------------------------------------------------------------------------------
00170 struct WO_DIRECT_INDIVIDUAL_MOTOR_CONTROL
00171 {
00172         unsigned char motor[8];
00173 
00174         /*
00175          * commands will be directly interpreted by each motor individually
00176          *
00177          * range: 0..200 = 0..100 %; 0 = motor off! Please check for command != 0 during flight, as a motor restart might take > 1s!
00178          */
00179 
00180         /*
00181          * Quadcopter (AscTec Hummingbird, AscTec Pelican)
00182          *
00183          * motor[0]: front
00184          * motor[1]: rear
00185          * motor[2]: left
00186          * motor[3]: right
00187          *
00188          */
00189 
00190         /*
00191          * Hexcopter (AscTec Firefly)
00192          *
00193          * motor[0]: front-left
00194          * motor[1]: left
00195          * motor[2]: rear-left
00196          * motor[3]: rear-right
00197          * motor[4]: right
00198          * motor[5]: front-right
00199          *
00200          */
00201 
00202 };
00203 extern struct WO_DIRECT_INDIVIDUAL_MOTOR_CONTROL WO_Direct_Individual_Motor_Control;
00204 
00205 struct WO_DIRECT_MOTOR_CONTROL //direct motor commands with standard output mapping
00206 {
00207         unsigned char pitch;
00208         unsigned char roll;
00209         unsigned char yaw;
00210         unsigned char thrust;
00211 
00212         /*
00213          * commands will be directly interpreted by the mixer
00214          * running on each of the motor controllers
00215          *
00216          * range (pitch, roll, yaw commands): 0..200 = - 100..+100 %
00217          * range of thrust command: 0..200 = 0..100 %
00218          */
00219 
00220 };
00221 extern struct WO_DIRECT_MOTOR_CONTROL WO_Direct_Motor_Control;
00222 
00223 
00224 //attitude commands
00225 
00226 struct WO_CTRL_INPUT {
00227 
00228         short pitch;    //pitch input: -2047..+2047 (0=neutral)
00229         short roll;             //roll input: -2047..+2047      (0=neutral)
00230         short yaw;              //(=R/C Stick input) -2047..+2047 (0=neutral)
00231         short thrust;   //collective: 0..4095 = 0..100%
00232         short ctrl;                             /*control byte:
00233                                                         bit 0: pitch control enabled
00234                                                         bit 1: roll control enabled
00235                                                         bit 2: yaw control enabled
00236                                                         bit 3: thrust control enabled
00237                                                         bit 4: height control enabled
00238                                                         bit 5: GPS position control enabled
00239                                                         */
00240 
00241         //max. pitch/roll (+-2047) equals 51.2° angle if GPS position control is disabled
00242         //max. pitch/roll (+-2047) equals approx. 3 m/s if GPS position control is active (GPS signal needed!)
00243 
00244 };
00245 extern struct WO_CTRL_INPUT WO_CTRL_Input;
00246 
00247 
00248 //waypoint commands
00249 
00250 struct WAYPOINT { //waypoint definition
00251 //always set to 1
00252   unsigned int wp_activated;
00253 
00254 //use WPPROP_* defines to set waypoint properties
00255   unsigned char properties;
00256 
00257 //max. speed to travel to waypoint in % (default 100)
00258   unsigned char max_speed;
00259 
00260 //time to stay at a waypoint (XYZ) in 1/100 s
00261   unsigned short time;
00262 
00263 //position accuracy to consider a waypoint reached in mm (recommended: 3000 (= 3.0 m))
00264   unsigned short pos_acc;
00265 
00266 //chksum = 0xAAAA + wp.yaw + wp.height + wp.time + wp.X + wp.Y + wp.max_speed + wp.pos_acc + wp.properties + wp.wp_number;
00267   short chksum;
00268 
00269  //relative waypoint coordinates in mm  // longitude in abs coords e.g. 113647430 (= 11.3647430°; angle in degrees * 10^7)
00270   int X;
00271  //relative waypoint coordinates in mm          // latitude in abs coords e.g. 480950480 (= 48.0950480°; angle in degrees * 10^7)
00272   int Y;
00273 
00274 //yaw angle
00275   int yaw; // 1/1000°
00276 
00277 //height over 0 reference in mm
00278   int height;
00279 
00280 };
00281 extern struct WAYPOINT wpToLL;
00282 
00283 //set waypoint properties with WPPROP_* defines (wpToLL.properties)
00284 #define WPPROP_ABSCOORDS                        0x01    //if set waypoint is interpreted as absolute coordinates, else relative coordinates
00285 #define WPPROP_HEIGHTENABLED            0x02    //set new height at waypoint
00286 #define WPPROP_YAWENABLED                       0x04    //set new yaw-angle at waypoint
00287 #define WPPROP_AUTOMATICGOTO            0x10    //if set, vehicle will not wait for a goto command, but goto this waypoint directly
00288 
00289 extern unsigned char wpCtrlWpCmd; //choose actual waypoint command from WP_CMD_* defines
00290 #define WP_CMD_SINGLE_WP        0x01 //fly to single waypoint
00291 #define WP_CMD_LAUNCH           0x02 //launch to 10m at current position
00292 #define WP_CMD_LAND                     0x03 //land at current position
00293 #define WP_CMD_GOHOME           0x04 //come home at current height. Home position is set when motors are started (valid GPS signal mandatory!) or with WP_CMD_SETHOME
00294 #define WP_CMD_SETHOME          0x05 //save current vehicle position as home position
00295 #define WP_CMD_ABORT            0x06 //abort navigation (stops current waypoint flying)
00296 
00297 extern unsigned char wpCtrlWpCmdUpdated; //send current waypoint command to LL
00298 extern unsigned char wpCtrlAckTrigger; //acknowledge from LL processor that waypoint was accepted
00299 
00300 //Waypoint navigation status
00301 extern unsigned short wpCtrlNavStatus; //check navigation status with WP_NAVSTAT_* defines
00302 #define WP_NAVSTAT_REACHED_POS                  0x01    //vehicle has entered a radius of WAYPOINT.pos_acc and time to stay is not necessarily over
00303 #define WP_NAVSTAT_REACHED_POS_TIME             0x02    //vehicle is within a radius of WAYPOINT.pos_acc and time to stay is over
00304 #define WP_NAVSTAT_20M                                  0x04    //vehicle within a 20m radius of the waypoint
00305 #define WP_NAVSTAT_PILOT_ABORT                  0x08    //waypoint navigation aborted by safety pilot (any stick was moved)
00306 
00307 extern unsigned short wpCtrlDistToWp; //current distance to the current waypoint in dm (=10 cm)
00308 
00309 #endif /*SDK_*/


asctec_hl_firmware
Author(s): Markus Achtelik, Michael Achtelik, Stephan Weiss, Laurent Kneip
autogenerated on Tue Jan 7 2014 11:05:19