sdk.h
Go to the documentation of this file.
00001 /*
00002 
00003 Copyright (c) 2011, Markus Achtelik, ASL, ETH Zurich, Switzerland
00004 You can contact the author at <markus dot achtelik at mavt dot ethz dot ch>
00005 
00006 All rights reserved.
00007 
00008 Redistribution and use in source and binary forms, with or without
00009 modification, are permitted provided that the following conditions are met:
00010 * Redistributions of source code must retain the above copyright
00011 notice, this list of conditions and the following disclaimer.
00012 * Redistributions in binary form must reproduce the above copyright
00013 notice, this list of conditions and the following disclaimer in the
00014 documentation and/or other materials provided with the distribution.
00015 * Neither the name of ETHZ-ASL nor the
00016 names of its contributors may be used to endorse or promote products
00017 derived from this software without specific prior written permission.
00018 
00019 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00020 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00021 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00022 DISCLAIMED. IN NO EVENT SHALL ETHZ-ASL BE LIABLE FOR ANY
00023 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00024 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00026 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00027 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00028 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029 
00030 */
00031 
00032 #ifndef SDK_H
00033 #define SDK_H
00034 
00035 #include <inttypes.h>
00036 
00037 #include "pid.h"
00038 #include "uart.h"
00039 #include "hardware.h"
00040 #include "kalman.h"
00041 #include "comm_util_LL.h"
00042 
00043 #define CMD_MAX_PERIOD 100 // in [ms] ==> 10Hz
00044 
00045 #define LAND_THRUST_DECREASE_STEP    0.01      // while landing, decrease thrust by this much
00046 #define LAND_THRUST_DECREASE_PERIOD  1      // while landing, decrease thrust every # of cycles
00047 
00048 typedef struct
00049 {
00050   Position x;     // x position, in m
00051   Position y;     // y position, in m
00052   Position z;     // z position, in m
00053 
00054   Velocity vx;    // x velocity, in m/sec
00055   Velocity vy;    // y velocity, in m/sec
00056   Velocity vz;    // y velocity, in m/sec
00057 
00058   Angle roll;  // roll  orientation, in rad
00059   Angle pitch; // pitch orientation, in rad
00060   Angle yaw;   // yaw   orientation, in rad
00061 } MAV_POSE_SI;
00062 
00063 typedef struct
00064 {
00065   Angle cmd_roll;      // roll  ,    in rad/....
00066   Angle cmd_pitch;     // pitch ,    in rad
00067   AngVelocity cmd_yaw_rate;  // yaw_rate , in rad/s
00068   Thrust cmd_thrust;    // thrust,    in %      [0, 100]
00069 
00070 } MAV_CTRL_CMD;
00071 
00072 typedef struct
00073 {
00074   Position x;     // desired x position, in mm
00075   Position y;     // desired y position, in mm
00076   Position z;     // desired z position, in mm
00077 
00078   Velocity vx;    // desired x velocity, in mm/sec
00079   Velocity vy;    // desired y velocity, in mm/sec
00080 
00081   Angle yaw;   // desired yaw   orientation, in deg/100, [0, 36000)
00082 } MAV_DES_POSE;
00083 
00084 extern void SDK_mainloop(void);
00085 
00086 void sdkInit(void);
00087 
00088 inline void writeCommand(short pitch, short roll, short yaw, short thrust, short ctrl, short enable);
00089 inline void sendImuData(void);
00090 inline void sendRcData(void);
00091 inline void sendFlightStateData(void);
00092 inline void sendMavPoseData(void);
00093 inline void sendStatusData(void);
00094 inline void sendCtrlDebugData(void);
00095 
00096 inline unsigned short isSerialEnabled(void);
00097 inline void feedbackBeep(void);
00098 inline void estop(void);
00099 
00100 inline void processKF(void);
00101 inline void processMotorStateChanges(void);
00102 inline void processFlightActionRequests(void);
00103 inline void processEngageDisengageTimeouts(void);
00104 inline void processLandingThrust(void);
00105 inline void processMotorCommands(void);
00106 inline void processSendData(void);
00107 
00109 /***
00110  * Timestamped packets get send around every 2 s to average the transmission delay.
00111  * Corrects at max 500 us per second. If the time offset is large, the server (host PC)
00112  * time is taken directly and synchronization starts from that time.
00113  */
00114 inline void synchronizeTime(void);
00115 
00117 //inline void watchdog(void);
00118 
00120 inline int checkTxPeriod(uint16_t period, uint16_t phase);
00121 
00122 struct WO_SDK_STRUCT
00123 {
00124   unsigned char ctrl_mode;
00125   //0x00: "standard scientific interface" => send R/C stick commands to LL
00126   //0x01:       direct motor control
00127   //0x02: waypoint control (not yet implemented)
00128 
00129   unsigned char ctrl_enabled; 
00130   //0x00: Control commands are ignored by LL processor
00131   //0x01: Control commands are accepted by LL processor
00132 };
00133 extern struct WO_SDK_STRUCT WO_SDK;
00134 
00135 struct RO_RC_DATA
00136 {
00137   unsigned short channel[8];
00138   /*
00139    * channel[0]: Pitch
00140    * channel[1]: Roll
00141    * channel[2]: Thrust
00142    * channel[3]: Yaw
00143    * channel[4]: Serial interface enable/disable
00144    * channel[5]: manual / height control / GPS + height control
00145    *
00146    * range of each channel: 0..4095
00147    */
00148 };
00149 extern struct RO_RC_DATA RO_RC_Data;
00150 
00151 struct WO_DIRECT_MOTOR_CONTROL
00152 {
00153   unsigned char pitch;
00154   unsigned char roll;
00155   unsigned char yaw;
00156   unsigned char thrust;
00157 
00158   /*
00159    * commands will be directly interpreted by the mixer
00160    * running on each of the motor controllers
00161    *
00162    * range (pitch, roll, yaw commands): 0..200 = - 100..+100 %
00163    * range of thrust command: 0..200 = 0..100 %
00164    */
00165 
00166 };
00167 extern struct WO_DIRECT_MOTOR_CONTROL WO_Direct_Motor_Control;
00168 
00169 struct WO_CTRL_INPUT
00170 { //serial commands (= Scientific Interface)
00171   short pitch; //Pitch input: -2047..+2047 (0=neutral)
00172   short roll; //Roll input: -2047..+2047        (0=neutral)
00173   short yaw; //(=R/C Stick input) -2047..+2047 (0=neutral)
00174   short thrust; //Collective: 0..4095 = 0..100%
00175   short ctrl; /*control byte:
00176    bit 0: pitch control enabled
00177    bit 1: roll control enabled
00178    bit 2: yaw control enabled
00179    bit 3: thrust control enabled
00180    bit 4: Height control enabled
00181    bit 5: GPS position control enabled
00182    */
00183 };
00184 extern struct WO_CTRL_INPUT WO_CTRL_Input;
00185 
00186 #endif // SDK_H


ccny_asctec_firmware
Author(s): Ivan Dryanovski, Roberto G. Valenti
autogenerated on Tue Jan 7 2014 11:04:32